All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | List of all members
gazebo::sensors::ContactSensor Class Reference

Contact sensor. More...

#include <sensors/sensors.hh>

Inheritance diagram for gazebo::sensors::ContactSensor:
Inheritance graph
[legend]

Public Member Functions

 ContactSensor ()
 Constructor.
virtual ~ContactSensor ()
 Destructor.
unsigned int GetCollisionContactCount (const std::string &_collisionName) const
 Return the number of contacts for an observed collision.
unsigned int GetCollisionCount () const
 Get the number of collisions that the sensor is observing.
std::string GetCollisionName (unsigned int _index) const
 Get a collision name at index _index.
msgs::Contacts GetContacts () const
 Get all the contacts for the ContactSensor.
std::map< std::string,
physics::Contact
GetContacts (const std::string &_collisionName)
 Gets contacts of a collision.
virtual void Init ()
 Initialize the sensor.
virtual bool IsActive ()
 Returns true if sensor generation is active.
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters.
virtual void Load (const std::string &_worldName)
 Load the sensor with default parameters.
- Public Member Functions inherited from gazebo::sensors::Sensor
 Sensor (SensorCategory _cat)
 Constructor.
virtual ~Sensor ()
 Destructor.
template<typename T >
event::ConnectionPtr ConnectUpdated (T _subscriber)
 Connect a signal that is triggered when the sensor is updated.
void DisconnectUpdated (event::ConnectionPtr &_c)
 Disconnect from a the updated signal.
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message.
SensorCategory GetCategory () const
 Get the category of the sensor.
common::Time GetLastMeasurementTime ()
 Return last measurement time.
common::Time GetLastUpdateTime ()
 Return last update time.
std::string GetName () const
 Get name.
std::string GetParentName () const
 Returns the name of the sensor parent.
virtual math::Pose GetPose () const
 Get the current pose.
std::string GetScopedName () const
 Get fully scoped name of the sensor.
virtual std::string GetTopic () const
 Returns the topic name as set in SDF.
std::string GetType () const
 Get sensor type.
double GetUpdateRate ()
 Get the update rate of the sensor.
bool GetVisualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
std::string GetWorldName () const
 Returns the name of the world the sensor is in.
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero.
virtual void SetActive (bool _value)
 Set whether the sensor is active or not.
virtual void SetParent (const std::string &_name)
 Set the parent of the sensor.
void SetUpdateRate (double _hz)
 Set the update rate of the sensor.
void Update (bool _force)
 Update the sensor.

Protected Member Functions

virtual void Fini ()
 Finalize the sensor.
virtual void UpdateImpl (bool _force)
 Update the sensor information.

Additional Inherited Members

- Protected Attributes inherited from gazebo::sensors::Sensor
bool active
 True if sensor generation is active.
std::vector< event::ConnectionPtrconnections
 All event connections.
common::Time lastMeasurementTime
 Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
common::Time lastUpdateTime
 Time of the last update.
transport::NodePtr node
 Node for communication.
std::string parentName
 Name of the parent.
std::vector< SensorPluginPtrplugins
 All the plugins for the sensor.
math::Pose pose
 Pose of the sensor.
transport::SubscriberPtr poseSub
 Subscribe to pose updates.
sdf::ElementPtr sdf
 Pointer the the SDF element for the sensor.
common::Time updatePeriod
 Desired time between updates, set indirectly by Sensor::SetUpdateRate.
gazebo::physics::WorldPtr world
 Pointer to the world.

Detailed Description

Contact sensor.

This sensor detects and reports contacts between objects

Constructor & Destructor Documentation

gazebo::sensors::ContactSensor::ContactSensor ( )

Constructor.

virtual gazebo::sensors::ContactSensor::~ContactSensor ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::sensors::ContactSensor::Fini ( )
protectedvirtual

Finalize the sensor.

Reimplemented from gazebo::sensors::Sensor.

unsigned int gazebo::sensors::ContactSensor::GetCollisionContactCount ( const std::string &  _collisionName) const

Return the number of contacts for an observed collision.

Parameters
[in]_collisionNameThe name of the observed collision.
Returns
The collision contact count.
unsigned int gazebo::sensors::ContactSensor::GetCollisionCount ( ) const

Get the number of collisions that the sensor is observing.

Returns
Number of collisions.
std::string gazebo::sensors::ContactSensor::GetCollisionName ( unsigned int  _index) const

Get a collision name at index _index.

Parameters
[in]_indexIndex of collision in collection of collisions.
Returns
name of collision.
msgs::Contacts gazebo::sensors::ContactSensor::GetContacts ( ) const

Get all the contacts for the ContactSensor.

Returns
Message that contains contact information between collision pairs.

During ODEPhysics::UpdateCollisions, all collision pairs in the world are pushed into a buffer within ContactManager. Subsequently, World::Update invokes ContactManager::PublishContacts to publish all contacts generated within a timestep onto Gazebo topic ~/physics/contacts.

Each ContactSensor subscribes to the Gazebo ~/physics/contacts topic, retrieves all contact pairs in a time step and filters them wthin ContactSensor::OnContacts against <collision> body name specified by the ContactSensor SDF. All collision pairs between ContactSensor <collision> body and other bodies in the world are stored in an array inside contacts.proto.

Within each element of the contact.proto array inside contacts.proto, list of collisions between collision bodies (collision1 and collision 2) are stored in an array of elements, (position, normal, depth, wrench). A timestamp has also been added (time). Details are described below:

  • string collision1 name of the first collision object.
  • string collision2 name of the second collision object.
  • Vector3d position position of the contact joint in inertial frame.
  • Vector3d normal normal of the contact joint in inertial frame.
  • double depth intersection (penetration) depth of two collision bodies.
  • JointWrench wrench Forces and torques acting on both collision bodies. See joint_wrench.proto for details. The forces and torques are applied at the CG of perspective links for each collision body, specified in the inertial frame.
  • Time time time at which this contact happened.
std::map<std::string, physics::Contact> gazebo::sensors::ContactSensor::GetContacts ( const std::string &  _collisionName)

Gets contacts of a collision.

Parameters
[in]_collisionNameName of collision
Returns
Container of contacts
virtual void gazebo::sensors::ContactSensor::Init ( )
virtual

Initialize the sensor.

Reimplemented from gazebo::sensors::Sensor.

virtual bool gazebo::sensors::ContactSensor::IsActive ( )
virtual

Returns true if sensor generation is active.

Returns
True if active, false if not.

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::ContactSensor::Load ( const std::string &  _worldName,
sdf::ElementPtr  _sdf 
)
virtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters
[in]_worldNameName of world to load from

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::ContactSensor::Load ( const std::string &  _worldName)
virtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from.

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::ContactSensor::UpdateImpl ( bool  _force)
protectedvirtual

Update the sensor information.

Parameters
[in]_forceTrue if update is forced, false if not.

Reimplemented from gazebo::sensors::Sensor.


The documentation for this class was generated from the following file: