gazebo_ros_bumper.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2012 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 <map>
00019 #include <string>
00020 
00021 #include <gazebo/physics/World.hh>
00022 #include <gazebo/physics/HingeJoint.hh>
00023 #include <gazebo/physics/Contact.hh>
00024 #include <gazebo/sensors/Sensor.hh>
00025 #include <gazebo/sdf/interface/SDF.hh>
00026 #include <gazebo/sdf/interface/Param.hh>
00027 #include <gazebo/common/Exception.hh>
00028 #include <gazebo/sensors/SensorTypes.hh>
00029 #include <gazebo/math/Pose.hh>
00030 #include <gazebo/math/Quaternion.hh>
00031 #include <gazebo/math/Vector3.hh>
00032 
00033 #include <tf/tf.h>
00034 
00035 #include "gazebo_plugins/gazebo_ros_bumper.h"
00036 
00037 namespace gazebo
00038 {
00039 // Register this plugin with the simulator
00040 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBumper)
00041 
00042 
00043 // Constructor
00044 GazeboRosBumper::GazeboRosBumper() : SensorPlugin()
00045 {
00046 }
00047 
00049 // Destructor
00050 GazeboRosBumper::~GazeboRosBumper()
00051 {
00052   this->rosnode_->shutdown();
00053   this->callback_queue_thread_.join();
00054 
00055   delete this->rosnode_;
00056 }
00057 
00059 // Load the controller
00060 void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00061 {
00062   this->parentSensor = boost::dynamic_pointer_cast<sensors::ContactSensor>(_parent);
00063   if (!this->parentSensor)
00064   {
00065     ROS_ERROR("Contact sensor parent is not of type ContactSensor");
00066     return;
00067   }
00068 
00069   this->robot_namespace_ = "";
00070   if (_sdf->HasElement("robotNamespace"))
00071     this->robot_namespace_ =
00072       _sdf->GetElement("robotNamespace")->GetValueString() + "/";
00073 
00074   // "publishing contact/collisions to this topic name: "
00075   //   << this->bumper_topic_name_ << std::endl;
00076   this->bumper_topic_name_ = "bumper_states";
00077   if (_sdf->GetElement("bumperTopicName"))
00078     this->bumper_topic_name_ =
00079       _sdf->GetElement("bumperTopicName")->GetValueString();
00080 
00081   // "transform contact/collisions pose, forces to this body (link) name: "
00082   //   << this->frame_name_ << std::endl;
00083   if (!_sdf->HasElement("frameName"))
00084   {
00085     ROS_INFO("bumper plugin missing <frameName>, defaults to world");
00086     this->frame_name_ = "world";
00087   }
00088   else
00089     this->frame_name_ = _sdf->GetElement("frameName")->GetValueString();
00090 
00091   // Exit if no ROS
00092   if (!ros::isInitialized())
00093   {
00094     gzerr << "Not loading plugin since ROS hasn't been "
00095           << "properly initialized.  Try starting gazebo with ros plugin:\n"
00096           << "  gazebo -s libgazebo_ros_api_plugin.so\n";
00097     return;
00098   }
00099 
00100   this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00101 
00102   // resolve tf prefix
00103   std::string prefix;
00104   this->rosnode_->getParam(std::string("tf_prefix"), prefix);
00105   this->frame_name_ = tf::resolve(prefix, this->frame_name_);
00106 
00107   this->contact_pub_ = this->rosnode_->advertise<gazebo_msgs::ContactsState>(
00108     std::string(this->bumper_topic_name_), 1);
00109 
00110   // Initialize
00111   // start custom queue for contact bumper
00112   this->callback_queue_thread_ = boost::thread(
00113       boost::bind(&GazeboRosBumper::ContactQueueThread, this));
00114 
00115   // Listen to the update event. This event is broadcast every
00116   // simulation iteration.
00117   this->update_connection_ = this->parentSensor->ConnectUpdated(
00118      boost::bind(&GazeboRosBumper::OnContact, this));
00119 }
00120 
00122 // Update the controller
00123 void GazeboRosBumper::OnContact()
00124 {
00125   if (this->contact_pub_.getNumSubscribers() <= 0)
00126     return;
00127 
00128   msgs::Contacts contacts;
00129   contacts = this->parentSensor->GetContacts();
00131   this->contact_state_msg_.header.frame_id = this->frame_name_;
00132   this->contact_state_msg_.header.stamp = ros::Time(contacts.time().sec(),
00133                                contacts.time().nsec());
00134 
00135 /*
00138 
00139   // if frameName specified is "world", "/map" or "map" report back
00140   // inertial values in the gazebo world
00141   physics::LinkPtr myFrame;
00142   if (myFrame == NULL && this->frame_name_ != "world" &&
00143     this->frame_name_ != "/map" && this->frame_name_ != "map")
00144   {
00145     // lock in case a model is being spawned
00146     boost::recursive_mutex::scoped_lock lock(
00147       *Simulator::Instance()->GetMRMutex());
00148     // look through all models in the world, search for body
00149     // name that matches frameName
00150     phyaics::Model_V all_models = World::Instance()->GetModels();
00151     for (physics::Model_V::iterator iter = all_models.begin();
00152       iter != all_models.end(); iter++)
00153     {
00154       if (*iter) myFrame =
00155         boost::dynamic_pointer_cast<physics::Link>((*iter)->GetLink(this->frame_name_));
00156       if (myFrame) break;
00157     }
00158 
00159     // not found
00160     if (!myFrame)
00161     {
00162       ROS_INFO("gazebo_ros_bumper plugin: frameName: %s does not exist"
00163                 " yet, will not publish\n",this->frame_name_.c_str());
00164       return;
00165     }
00166   }
00167 */
00168   // get reference frame (body(link)) pose and subtract from it to get
00169   // relative force, torque, position and normal vectors
00170   math::Pose pose, frame_pose;
00171   math::Quaternion rot, frame_rot;
00172   math::Vector3 pos, frame_pos;
00173   /*
00174   if (myFrame)
00175   {
00176     frame_pose = myFrame->GetWorldPose();  //-this->myBody->GetCoMPose();
00177     frame_pos = frame_pose.pos;
00178     frame_rot = frame_pose.rot;
00179   }
00180   else
00181   */
00182   {
00183     // no specific frames specified, use identity pose, keeping
00184     // relative frame at inertial origin
00185     frame_pos = math::Vector3(0, 0, 0);
00186     frame_rot = math::Quaternion(1, 0, 0, 0);  // gazebo u,x,y,z == identity
00187     frame_pose = math::Pose(frame_pos, frame_rot);
00188   }
00189 
00190 
00191 
00192   // set contact states size
00193   this->contact_state_msg_.states.clear();
00194 
00195   // GetContacts returns all contacts on the collision body
00196   unsigned int contactsPacketSize = contacts.contact_size();
00197   for (unsigned int i = 0; i < contactsPacketSize; ++i)
00198   {
00199 
00200     // For each collision contact
00201     // Create a ContactState
00202     gazebo_msgs::ContactState state;
00204     gazebo::msgs::Contact contact = contacts.contact(i);
00205 
00206     state.collision1_name = contact.collision1();
00207     state.collision2_name = contact.collision2();
00208     std::ostringstream stream;
00209     stream << "Debug:  i:(" << i << "/" << contactsPacketSize
00210       << ")     my geom:" << state.collision1_name
00211       << "   other geom:" << state.collision2_name
00212       << "         time:" << ros::Time(contact.time().sec(), contact.time().nsec())
00213       << std::endl;
00214     state.info = stream.str();
00215 
00216     state.wrenches.clear();
00217     state.contact_positions.clear();
00218     state.contact_normals.clear();
00219     state.depths.clear();
00220 
00221     // sum up all wrenches for each DOF
00222     geometry_msgs::Wrench total_wrench;
00223     total_wrench.force.x = 0;
00224     total_wrench.force.y = 0;
00225     total_wrench.force.z = 0;
00226     total_wrench.torque.x = 0;
00227     total_wrench.torque.y = 0;
00228     total_wrench.torque.z = 0;
00229 
00230     unsigned int contactGroupSize = contact.position_size();
00231     for (unsigned int j = 0; j < contactGroupSize; ++j)
00232     {
00233       // loop through individual contacts between collision1 and collision2
00234       // gzerr << j << "  Position:"
00235       //       << contact.position(j).x() << " "
00236       //       << contact.position(j).y() << " "
00237       //       << contact.position(j).z() << "\n";
00238       // gzerr << "   Normal:"
00239       //       << contact.normal(j).x() << " "
00240       //       << contact.normal(j).y() << " "
00241       //       << contact.normal(j).z() << "\n";
00242       // gzerr << "   Depth:" << contact.depth(j) << "\n";
00243 
00244       // Get force, torque and rotate into user specified frame.
00245       // frame_rot is identity if world is used (default for now)
00246       math::Vector3 force = frame_rot.RotateVectorReverse(math::Vector3(
00247                             contact.wrench(j).body_1_force().x(),
00248                             contact.wrench(j).body_1_force().y(),
00249                             contact.wrench(j).body_1_force().z()));
00250       math::Vector3 torque = frame_rot.RotateVectorReverse(math::Vector3(
00251                             contact.wrench(j).body_1_torque().x(),
00252                             contact.wrench(j).body_1_torque().y(),
00253                             contact.wrench(j).body_1_torque().z()));
00254 
00255       // set wrenches
00256       geometry_msgs::Wrench wrench;
00257       wrench.force.x  = force.x;
00258       wrench.force.y  = force.y;
00259       wrench.force.z  = force.z;
00260       wrench.torque.x = torque.x;
00261       wrench.torque.y = torque.y;
00262       wrench.torque.z = torque.z;
00263       state.wrenches.push_back(wrench);
00264 
00265       total_wrench.force.x  += wrench.force.x;
00266       total_wrench.force.y  += wrench.force.y;
00267       total_wrench.force.z  += wrench.force.z;
00268       total_wrench.torque.x += wrench.torque.x;
00269       total_wrench.torque.y += wrench.torque.y;
00270       total_wrench.torque.z += wrench.torque.z;
00271 
00272       // transform contact positions into relative frame
00273       // set contact positions
00274       gazebo::math::Vector3 position = frame_rot.RotateVectorReverse(
00275           math::Vector3(contact.position(j).x(),
00276                         contact.position(j).y(),
00277                         contact.position(j).z()) - frame_pos);
00278       geometry_msgs::Vector3 contact_position;
00279       contact_position.x = position.x;
00280       contact_position.y = position.y;
00281       contact_position.z = position.z;
00282       state.contact_positions.push_back(contact_position);
00283 
00284       // rotate normal into user specified frame.
00285       // frame_rot is identity if world is used.
00286       math::Vector3 normal = frame_rot.RotateVectorReverse(
00287           math::Vector3(contact.normal(j).x(),
00288                         contact.normal(j).y(),
00289                         contact.normal(j).z()));
00290       // set contact normals
00291       geometry_msgs::Vector3 contact_normal;
00292       contact_normal.x = normal.x;
00293       contact_normal.y = normal.y;
00294       contact_normal.z = normal.z;
00295       state.contact_normals.push_back(contact_normal);
00296 
00297       // set contact depth, interpenetration
00298       state.depths.push_back(contact.depth(j));
00299     }
00300 
00301     state.total_wrench = total_wrench;
00302     this->contact_state_msg_.states.push_back(state);
00303   }
00304 
00305   this->contact_pub_.publish(this->contact_state_msg_);
00306 }
00307 
00308 
00310 // Put laser data to the interface
00311 void GazeboRosBumper::ContactQueueThread()
00312 {
00313   static const double timeout = 0.01;
00314 
00315   while (this->rosnode_->ok())
00316   {
00317     this->contact_queue_.callAvailable(ros::WallDuration(timeout));
00318   }
00319 }
00320 }


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Mon Oct 6 2014 12:15:44