Plugin that implements an optical tactile sensor. More...
#include <OpticalTactilePlugin.hh>
Public Member Functions | |
OpticalTactilePlugin () | |
Constructor. More... | |
~OpticalTactilePlugin () override=default | |
Destructor. More... | |
void | Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override |
Configure the system. More... | |
void | PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) override |
void | PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override |
Documentation inherited. More... | |
Public Member Functions inherited from System | |
System ()=default | |
Constructor. More... | |
virtual | ~System ()=default |
Destructor. More... | |
Detailed Description
Plugin that implements an optical tactile sensor.
It requires that contact sensor and depth camera be placed in at least one link on the model on which this plugin is attached. TODO: Currently, the contacts returned from the physics engine (which tends to be sparse) and the normal forces separately computed from the depth camera (which is dense, resolution adjustable) are disjoint. It is left as future work to combine the two sets of data.
Parameters:
<enabled> Set this to true so the plugin works from the start and doesn't need to be enabled. This element is optional, and the default value is true.
<namespace> Namespace for transport topics/services. If there are more than one optical tactile plugins, their namespaces should be different. This element is optional, and the default value is "optical_tactile_sensor". /<namespace>/enable : Service used to enable and disable the plugin. /<namespace>/normal_forces : Topic where a message is published each time the normal forces are computed
<visualization_resolution> Number n of pixels to skip when visualizing the forces. One vector representing a normal force is computed for every nth pixel. This element must be positive and it is optional. The default value is 30.
<force_length> Length in meters of the forces visualized if <visualize_forces> is set to true. This parameter is optional, and the default value is 0.01.
<extended_sensing> Extended sensing distance in meters. The sensor will output data coming from its collision geometry plus this distance. This element is optional, and the default value is 0.001.
<visualize_sensor> Whether to visualize the sensor or not. This element is optional, and the default value is false.
<visualize_contacts> Whether to visualize the contacts from the contact sensor based on physics. This element is optional, and the default value is false.
<visualize_forces> Whether to visualize normal forces computed from the depth camera. This element is optional, and the default value is false.
Constructor & Destructor Documentation
◆ OpticalTactilePlugin()
Constructor.
◆ ~OpticalTactilePlugin()
|
overridedefault |
Destructor.
Member Function Documentation
◆ Configure()
|
overridevirtual |
Configure the system.
- Parameters
-
[in] _entity The entity this plugin is attached to. [in] _sdf The SDF Element associated with this system plugin. [in] _ecm The EntityComponentManager of the given simulation instance. [in] _eventMgr The EventManager of the given simulation instance.
Implements ISystemConfigure.
◆ PostUpdate()
|
overridevirtual |
Implements ISystemPostUpdate.
◆ PreUpdate()
|
overridevirtual |
Documentation inherited.
Implements ISystemPreUpdate.
The documentation for this class was generated from the following file: