-
Notifications
You must be signed in to change notification settings - Fork 4
mujoco_contact_surface_sensors
mujoco_contact_surface_sensors is a separate ros package depending on mujoco_contact_surfaces.
Currently two different tactile sensors are implemented in this package. These are described in the following sections.
This sensor implements a tactile array similar to the Myrmex sensor. All taxels in the array are on one straight plane.
A demo of a Myrmex-like sensor can be started with roslaunch mujoco_contact_surface_sensors myrmex_sensor.launch
.
The mujoco_contact_surfaces plugin needs to be added to the MujocoPlugins parameters. To instantiate the sensor additional parameters have to be given like in the myrmex_sensor example:
MujocoPlugins:
- type: mujoco_contact_surfaces/MujocoContactSurfacesPlugin
SurfacePlugins:
- {
type: mujoco_contact_surface_sensors/FlatTactileSensor,
sensorName: "myrmex_sensor0",
geomName: "myrmex_foam",
topicName: "/tactile_module_16x16_v2",
updateRate: 50.0,
visualize: False,
resolution: 0.025
}
The semantics of the parameters are listed in the following table:
Parameter | Description |
---|---|
type |
Type of the sensor. |
sensorName |
Name of the sensor. |
geomName |
Name of the geom this sensor is attached to. The geom needs to be declared as soft in the mujoco xml parameters. For the FlatTactileSensor the geom needs to be a box. The sensor surface is the top surface of that box. |
topicName |
ROS topic name to publish the sensor data. The data is published as a tactile_msgs::TactileState. |
updateRate |
Publish frequency of the sensor in Hertz. |
visualize |
If set to True active taxels of the sensor will be visualized. Red indicates higher pressure, blue lower pressure. |
resolution |
Determines the number of cells in the sensor: |
In contrast to the FlatTactileSensor cells in the TaxelSensor can be placed at arbitray user defined positions.
A demo of a Myrmex-like sensor implemented as TaxelSensor can be started with roslaunch mujoco_contact_surface_sensors flat_taxel_test.launch
.
The mujoco_contact_surfaces plugin needs to be added to the MujocoPlugins parameters. To instantiate the sensor additional parameters have to be given like in the flat_taxel_sensor example:
MujocoPlugins:
- type: mujoco_contact_surfaces/MujocoContactSurfacesPlugin
SurfacePlugins:
- {
type: mujoco_contact_surface_sensors/TaxelSensor,
sensorName: "myrmex_sensor0",
geomName: "myrmex_foam",
topicName: "/tactile_module_16x16_v2",
updateRate: 50.0,
visualize: True,
include_margin: 0.01266666666666666,
method: "weighted",
sample_resolution: 0.01,
taxels:
[
[-0.19, -0.19, 0.02],
[-0.19, -0.16466666666666668, 0.02],
...
[0.19, 0.16466666666666668, 0.02],
[0.19, 0.19, 0.02],
],
}
The semantics of the parameters are listed in the following table:
Parameter | Description |
---|---|
type |
Type of the sensor. |
sensorName |
Name of the sensor. |
geomName |
Name of the geom this sensor is attached to. The geom needs to be declared as soft in the mujoco xml parameters. |
topicName |
ROS topic name to publish the sensor data. The data is published as a tactile_msgs::TactileState. |
updateRate |
Publish frequency of the sensor in Hertz. |
visualize |
If set to True active taxels will be visualized as arrows. Longer arrows indicate more pressure. Points on the contact surface from which the pressure was sampled are visualized in blue. |
include_margin |
Maximum distance a sample point on the contact surface can have to a taxel to still be considered for pressure calculation in that taxel. |
method |
Method used for pressure calculation in the taxels. Options are closest and weighted . closest only considers the pressure at the closest sample point on the contact surface for each taxel. weighted does a distance weighted average over the pressure of all sample points that are within include_margin away from the taxel location for each taxel. |
sample_resolution |
Resolution of sample points on the contact surface that are considered for pressure calculation. For smaller values the precision of data the sensor produces should go up but the computation speed of the sensor will go down. |
taxels |
Position of taxels relative position of the geom the sensor is attached to. |