27 #include <gazebo/physics/World.hh>
28 #include <gazebo/physics/HingeJoint.hh>
29 #include <gazebo/physics/Contact.hh>
30 #include <gazebo/sensors/Sensor.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>
39 #ifdef ENABLE_PROFILER
40 #include <ignition/common/Profiler.hh>
51 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosBumper)
74 this->
parentSensor = dynamic_pointer_cast<sensors::ContactSensor>(_parent);
77 ROS_ERROR_NAMED(
"bumper",
"Contact sensor parent is not of type ContactSensor");
82 if (_sdf->HasElement(
"robotNamespace"))
84 _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
89 if (_sdf->HasElement(
"bumperTopicName"))
90 this->bumper_topic_name_ =
91 _sdf->GetElement(
"bumperTopicName")->Get<std::string>();
95 if (!_sdf->HasElement(
"frameName"))
97 ROS_INFO_NAMED(
"bumper",
"bumper plugin missing <frameName>, defaults to world");
101 this->
frame_name_ = _sdf->GetElement(
"frameName")->Get<std::string>();
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)");
119 std::string(this->bumper_topic_name_), 1);
139 #ifdef ENABLE_PROFILER
140 IGN_PROFILE(
"GazeboRosBumper::OnContact");
145 #ifdef ENABLE_PROFILER
146 IGN_PROFILE_BEGIN(
"fill message");
148 msgs::Contacts contacts;
153 contacts.time().nsec());
190 ignition::math::Pose3d pose, frame_pose;
191 ignition::math::Quaterniond rot, frame_rot;
192 ignition::math::Vector3d pos, frame_pos;
205 frame_pos = ignition::math::Vector3d(0, 0, 0);
206 frame_rot = ignition::math::Quaterniond(1, 0, 0, 0);
207 frame_pose = ignition::math::Pose3d(frame_pos, frame_rot);
216 unsigned int contactsPacketSize = contacts.contact_size();
217 for (
unsigned int i = 0; i < contactsPacketSize; ++i)
222 gazebo_msgs::ContactState state;
224 gazebo::msgs::Contact contact = contacts.contact(i);
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())
234 state.info = stream.str();
236 state.wrenches.clear();
237 state.contact_positions.clear();
238 state.contact_normals.clear();
239 state.depths.clear();
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;
250 unsigned int contactGroupSize = contact.position_size();
251 for (
unsigned int j = 0; j < contactGroupSize; ++j)
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()));
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);
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;
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);
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()));
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);
318 state.depths.push_back(contact.depth(j));
321 state.total_wrench = total_wrench;
324 #ifdef ENABLE_PROFILER
326 IGN_PROFILE_BEGIN(
"publish");
329 #ifdef ENABLE_PROFILER
339 static const double timeout = 0.01;