gazebo_ros_bumper.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 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 /*
19  * Desc: Bumper controller
20  * Author: Nate Koenig
21  * Date: 09 Sept. 2008
22  */
23 
24 #include <map>
25 #include <string>
26 
27 #include <gazebo/physics/World.hh>
28 #include <gazebo/physics/HingeJoint.hh>
29 #include <gazebo/physics/Contact.hh>
30 #include <gazebo/sensors/Sensor.hh>
31 #include <sdf/sdf.hh>
32 #include <sdf/Param.hh>
33 #include <gazebo/common/Exception.hh>
34 #include <gazebo/sensors/SensorTypes.hh>
35 #include <ignition/math/Pose3.hh>
36 #include <ignition/math/Quaternion.hh>
37 #include <ignition/math/Vector3.hh>
38 
39 #ifdef ENABLE_PROFILER
40 #include <ignition/common/Profiler.hh>
41 #endif
42 
43 #include <tf/tf.h>
44 
47 
48 namespace gazebo
49 {
50 // Register this plugin with the simulator
51 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBumper)
52 
53 // Constructor
55 GazeboRosBumper::GazeboRosBumper() : SensorPlugin()
56 {
57 }
58 
60 // Destructor
62 {
63  this->rosnode_->shutdown();
64  this->callback_queue_thread_.join();
65 
66  delete this->rosnode_;
67 }
68 
70 // Load the controller
71 void GazeboRosBumper::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
72 {
74  this->parentSensor = dynamic_pointer_cast<sensors::ContactSensor>(_parent);
75  if (!this->parentSensor)
76  {
77  ROS_ERROR_NAMED("bumper", "Contact sensor parent is not of type ContactSensor");
78  return;
79  }
80 
81  this->robot_namespace_ = "";
82  if (_sdf->HasElement("robotNamespace"))
83  this->robot_namespace_ =
84  _sdf->GetElement("robotNamespace")->Get<std::string>() + "/";
85 
86  // "publishing contact/collisions to this topic name: "
87  // << this->bumper_topic_name_ << std::endl;
88  this->bumper_topic_name_ = "bumper_states";
89  if (_sdf->HasElement("bumperTopicName"))
90  this->bumper_topic_name_ =
91  _sdf->GetElement("bumperTopicName")->Get<std::string>();
92 
93  // "transform contact/collisions pose, forces to this body (link) name: "
94  // << this->frame_name_ << std::endl;
95  if (!_sdf->HasElement("frameName"))
96  {
97  ROS_INFO_NAMED("bumper", "bumper plugin missing <frameName>, defaults to world");
98  this->frame_name_ = "world";
99  }
100  else
101  this->frame_name_ = _sdf->GetElement("frameName")->Get<std::string>();
102 
103  // Make sure the ROS node for Gazebo has already been initialized
104  if (!ros::isInitialized())
105  {
106  ROS_FATAL_STREAM_NAMED("bumper", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
107  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
108  return;
109  }
110 
111  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
112 
113  // resolve tf prefix
114  std::string prefix;
115  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
116  this->frame_name_ = tf::resolve(prefix, this->frame_name_);
117 
118  this->contact_pub_ = this->rosnode_->advertise<gazebo_msgs::ContactsState>(
119  std::string(this->bumper_topic_name_), 1);
120 
121  // Initialize
122  // start custom queue for contact bumper
123  this->callback_queue_thread_ = boost::thread(
124  boost::bind(&GazeboRosBumper::ContactQueueThread, this));
125 
126  // Listen to the update event. This event is broadcast every
127  // simulation iteration.
128  this->update_connection_ = this->parentSensor->ConnectUpdated(
129  boost::bind(&GazeboRosBumper::OnContact, this));
130 
131  // Make sure the parent sensor is active.
132  this->parentSensor->SetActive(true);
133 }
134 
136 // Update the controller
138 {
139 #ifdef ENABLE_PROFILER
140  IGN_PROFILE("GazeboRosBumper::OnContact");
141 #endif
142  if (this->contact_pub_.getNumSubscribers() <= 0)
143  return;
144 
145 #ifdef ENABLE_PROFILER
146  IGN_PROFILE_BEGIN("fill message");
147 #endif
148  msgs::Contacts contacts;
149  contacts = this->parentSensor->Contacts();
151  this->contact_state_msg_.header.frame_id = this->frame_name_;
152  this->contact_state_msg_.header.stamp = ros::Time(contacts.time().sec(),
153  contacts.time().nsec());
154 
155 /*
158 
159  // if frameName specified is "world", "/map" or "map" report back
160  // inertial values in the gazebo world
161  physics::LinkPtr myFrame;
162  if (myFrame == NULL && this->frame_name_ != "world" &&
163  this->frame_name_ != "/map" && this->frame_name_ != "map")
164  {
165  // lock in case a model is being spawned
166  boost::recursive_mutex::scoped_lock lock(
167  *Simulator::Instance()->GetMRMutex());
168  // look through all models in the world, search for body
169  // name that matches frameName
170  physics::Model_V all_models = World::Instance()->Models();
171  for (physics::Model_V::iterator iter = all_models.begin();
172  iter != all_models.end(); iter++)
173  {
174  if (*iter) myFrame =
175  boost::dynamic_pointer_cast<physics::Link>((*iter)->GetLink(this->frame_name_));
176  if (myFrame) break;
177  }
178 
179  // not found
180  if (!myFrame)
181  {
182  ROS_INFO_NAMED("bumper", "gazebo_ros_bumper plugin: frameName: %s does not exist"
183  " yet, will not publish\n",this->frame_name_.c_str());
184  return;
185  }
186  }
187 */
188  // get reference frame (body(link)) pose and subtract from it to get
189  // relative force, torque, position and normal vectors
190  ignition::math::Pose3d pose, frame_pose;
191  ignition::math::Quaterniond rot, frame_rot;
192  ignition::math::Vector3d pos, frame_pos;
193  /*
194  if (myFrame)
195  {
196  frame_pose = myFrame->WorldPose(); //-this->myBody->GetCoMPose();
197  frame_pos = frame_pose.Pos();
198  frame_rot = frame_pose.Rot();
199  }
200  else
201  */
202  {
203  // no specific frames specified, use identity pose, keeping
204  // relative frame at inertial origin
205  frame_pos = ignition::math::Vector3d(0, 0, 0);
206  frame_rot = ignition::math::Quaterniond(1, 0, 0, 0); // gazebo u,x,y,z == identity
207  frame_pose = ignition::math::Pose3d(frame_pos, frame_rot);
208  }
209 
210 
211 
212  // set contact states size
213  this->contact_state_msg_.states.clear();
214 
215  // GetContacts returns all contacts on the collision body
216  unsigned int contactsPacketSize = contacts.contact_size();
217  for (unsigned int i = 0; i < contactsPacketSize; ++i)
218  {
219 
220  // For each collision contact
221  // Create a ContactState
222  gazebo_msgs::ContactState state;
224  gazebo::msgs::Contact contact = contacts.contact(i);
225 
226  state.collision1_name = contact.collision1();
227  state.collision2_name = contact.collision2();
228  std::ostringstream stream;
229  stream << "Debug: i:(" << i << "/" << contactsPacketSize
230  << ") my geom:" << state.collision1_name
231  << " other geom:" << state.collision2_name
232  << " time:" << ros::Time(contact.time().sec(), contact.time().nsec())
233  << std::endl;
234  state.info = stream.str();
235 
236  state.wrenches.clear();
237  state.contact_positions.clear();
238  state.contact_normals.clear();
239  state.depths.clear();
240 
241  // sum up all wrenches for each DOF
242  geometry_msgs::Wrench total_wrench;
243  total_wrench.force.x = 0;
244  total_wrench.force.y = 0;
245  total_wrench.force.z = 0;
246  total_wrench.torque.x = 0;
247  total_wrench.torque.y = 0;
248  total_wrench.torque.z = 0;
249 
250  unsigned int contactGroupSize = contact.position_size();
251  for (unsigned int j = 0; j < contactGroupSize; ++j)
252  {
253  // loop through individual contacts between collision1 and collision2
254  // gzerr << j << " Position:"
255  // << contact.position(j).x() << " "
256  // << contact.position(j).y() << " "
257  // << contact.position(j).z() << "\n";
258  // gzerr << " Normal:"
259  // << contact.normal(j).x() << " "
260  // << contact.normal(j).y() << " "
261  // << contact.normal(j).z() << "\n";
262  // gzerr << " Depth:" << contact.depth(j) << "\n";
263 
264  // Get force, torque and rotate into user specified frame.
265  // frame_rot is identity if world is used (default for now)
266  ignition::math::Vector3d force = frame_rot.RotateVectorReverse(ignition::math::Vector3d(
267  contact.wrench(j).body_1_wrench().force().x(),
268  contact.wrench(j).body_1_wrench().force().y(),
269  contact.wrench(j).body_1_wrench().force().z()));
270  ignition::math::Vector3d torque = frame_rot.RotateVectorReverse(ignition::math::Vector3d(
271  contact.wrench(j).body_1_wrench().torque().x(),
272  contact.wrench(j).body_1_wrench().torque().y(),
273  contact.wrench(j).body_1_wrench().torque().z()));
274 
275  // set wrenches
276  geometry_msgs::Wrench wrench;
277  wrench.force.x = force.X();
278  wrench.force.y = force.Y();
279  wrench.force.z = force.Z();
280  wrench.torque.x = torque.X();
281  wrench.torque.y = torque.Y();
282  wrench.torque.z = torque.Z();
283  state.wrenches.push_back(wrench);
284 
285  total_wrench.force.x += wrench.force.x;
286  total_wrench.force.y += wrench.force.y;
287  total_wrench.force.z += wrench.force.z;
288  total_wrench.torque.x += wrench.torque.x;
289  total_wrench.torque.y += wrench.torque.y;
290  total_wrench.torque.z += wrench.torque.z;
291 
292  // transform contact positions into relative frame
293  // set contact positions
294  ignition::math::Vector3d position = frame_rot.RotateVectorReverse(
295  ignition::math::Vector3d(contact.position(j).x(),
296  contact.position(j).y(),
297  contact.position(j).z()) - frame_pos);
298  geometry_msgs::Vector3 contact_position;
299  contact_position.x = position.X();
300  contact_position.y = position.Y();
301  contact_position.z = position.Z();
302  state.contact_positions.push_back(contact_position);
303 
304  // rotate normal into user specified frame.
305  // frame_rot is identity if world is used.
306  ignition::math::Vector3d normal = frame_rot.RotateVectorReverse(
307  ignition::math::Vector3d(contact.normal(j).x(),
308  contact.normal(j).y(),
309  contact.normal(j).z()));
310  // set contact normals
311  geometry_msgs::Vector3 contact_normal;
312  contact_normal.x = normal.X();
313  contact_normal.y = normal.Y();
314  contact_normal.z = normal.Z();
315  state.contact_normals.push_back(contact_normal);
316 
317  // set contact depth, interpenetration
318  state.depths.push_back(contact.depth(j));
319  }
320 
321  state.total_wrench = total_wrench;
322  this->contact_state_msg_.states.push_back(state);
323  }
324 #ifdef ENABLE_PROFILER
325  IGN_PROFILE_END();
326  IGN_PROFILE_BEGIN("publish");
327 #endif
329 #ifdef ENABLE_PROFILER
330  IGN_PROFILE_END();
331 #endif
332 }
333 
334 
336 // Put laser data to the interface
338 {
339  static const double timeout = 0.01;
340 
341  while (this->rosnode_->ok())
342  {
344  }
345 }
346 }
gazebo_ros_bumper.h
gazebo::GazeboRosBumper::frame_name_
std::string frame_name_
Definition: gazebo_ros_bumper.h:77
gazebo::GazeboRosBumper
A Bumper controller.
Definition: gazebo_ros_bumper.h:53
gazebo::GazeboRosBumper::~GazeboRosBumper
~GazeboRosBumper()
Destructor.
Definition: gazebo_ros_bumper.cpp:61
gazebo
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo::GazeboRosBumper::bumper_topic_name_
std::string bumper_topic_name_
set topic name of broadcast
Definition: gazebo_ros_bumper.h:75
gazebo::GazeboRosBumper::contact_pub_
ros::Publisher contact_pub_
Definition: gazebo_ros_bumper.h:70
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosBumper::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_bumper.h:83
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosBumper::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_bumper.h:90
gazebo::GazeboRosBumper::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_bumper.h:69
gazebo::GazeboRosBumper::ContactQueueThread
void ContactQueueThread()
Definition: gazebo_ros_bumper.cpp:337
gazebo::GazeboRosBumper::contact_state_msg_
gazebo_msgs::ContactsState contact_state_msg_
broadcast some string for now.
Definition: gazebo_ros_bumper.h:80
tf.h
ros::NodeHandle::ok
bool ok() const
ros::Time
gazebo::GazeboRosBumper::contact_queue_
ros::CallbackQueue contact_queue_
Definition: gazebo_ros_bumper.h:85
gazebo::GazeboRosBumper::parentSensor
sensors::ContactSensorPtr parentSensor
Definition: gazebo_ros_bumper.h:72
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
gazebo::GazeboRosBumper::OnContact
void OnContact()
Update the controller.
Definition: gazebo_ros_bumper.cpp:137
gazebo_ros_utils.h
ros::WallDuration
ros::NodeHandle::shutdown
void shutdown()
ros::CallbackQueue::callAvailable
void callAvailable()
GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
Definition: gazebo_ros_utils.h:49
gazebo::GazeboRosBumper::Load
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
Definition: gazebo_ros_bumper.cpp:71
ros::NodeHandle
gazebo::GazeboRosBumper::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_bumper.h:87


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28