|
3.43 TouchSensorDerived from Solid.
3.43.1 DescriptionA TouchSensor node is used to model a "bumper" sensor or a "force" sensor. A "bumper" sensor simply detects collisions and returns a boolean, while a "force" sensor indicates the actual pressure exerted by external objects. The TouchSensor node includes these two specific fields:
3.43.2 Bumper SensorsA "bumper" sensor returns a boolean value that indicates whether or not there is a collision with another object. More precisely, it returns 1 if a collision was detected at the previous time step, and 0 otherwise. A collision is detected when the boundingObject of the TouchSensor intersects the boundingObject of any other Solid object. Note that a "bumper" TouchSensor is effective only if its boundingObject is defined (not NULL). The lookupTable field is not used by bumper sensors. An example of using a bumper sensor is provided in the bumper.wbt sample world (located in the projects/samples/devices/worlds directory of Webots). 3.43.3 Force SensorsA "force" TouchSensor return an integer value that indicates the magnitude of the force currently exerted on the sensor. The force is measured in the direction of the sensor's z-axis; forces in other directions are ignored. For this reason, a force sensor must always be oriented such that its positive z-axis point in the direction where the collision is expected, which is usually outward from the robot body. A "force" sensor uses the lookupTable to model the non-linearity (and saturation) of a real pressure sensor. The lookupTable allows you to map the simulated force measured in N (Newtons) to an output value that will be returned by the wb_touch_sensor_get_value() function. The value returned by the force sensor is first computed by the ODE physics engine, then interpolated using the lookupTable, and finally noise is added (if specified). Each line of the lookupTable contains three numbers: (1) an input force in Newtons, (2) the corresponding integer output value, and (3) a noise level between 0 and 1 (see DistanceSensor for more info). Note that the default lookupTable of a TouchSensor node maps forces between 0 and 5000 Newtons to integer values between 0 and 50000; therefore you will usually want to divide the returned values by 10. The force measured by the ODE physics engine is only a rough approximation of real physical pressure. Usually the approximation of reality improves as the basicTimeStep (WorldInfo node) decreases. Note that a "force" TouchSensor is effective only when both its boundingObject and physics fields are defined (not NULL). Note: It is easy to check if the z-axis of a TouchSensor points in the correct direction: if you select the TouchSensor object in the Scene Tree, then only the bounding object of this TouchSensor should be displayed in the main window. If you zoom in on this bounding object, you should see the red/green/blue depiction of the TouchSensor's coordinate system (the color coding is: x/y/z = red/green/blue). The blue (z) component should point in the direction where the collision is expected. Two examples of using a force sensor are provided in the hoap2_sumo.wbt and hoap2_walk.wbt sample worlds (located in the projects/robots/hoap2/worlds directory of Webots). 3.43.4 Collision detectionBoth "bumper" and "force" TouchSensors detect collisions based on the 3D geometry of their boundingObjects. Because the actual 3d intersection of the sensors boundingObjects with other boundingObjects is used in the calculation, it is very important that the sensors' boundingObjects are placed correctly on the robot; they should have a chance to contact other objects, otherwise they are ineffective. For that reason, the volume of the boundingObjects of TouchSensors should always extend beyond other boundingObjects of the robot in the area where the collision is expected, that is, in the direction of the positive z-axis. For example, let's assume that you want to add a TouchSensor under the foot of a humanoid robot. In this case, it is critical that the boundingObject of the TouchSensor (and not any other boundingObject of the robot) makes the actual contact with the ground. Therefore, it is necessary that the sensor's boundingObject extend below any other boundingObject of the robot (e.g. foot, ankle, etc.). 3.43.5 TouchSensor FunctionsNAMEwb_touch_sensor_enable, wb_touch_sensor_disable - enable and disable touch sensor measurementsC SYNOPSIS#include <webots/touch_sensor.h>void wb_touch_sensor_enable(WbDeviceTag sensor, int ms); void wb_touch_sensor_disable(WbDeviceTag sensor); C++ SYNOPSIS#include <webots/TouchSensor.hpp>void TouchSensor::enable(int ms); void TouchSensor::disable(); JAVA SYNOPSISimport com.cyberbotics.webots.controller.TouchSensor;void TouchSensor.enable(int ms); void TouchSensor.disable(); PYTHON SYNOPSISfrom controller import TouchSensornone TouchSensor.enable(int ms) none TouchSensor.disable() DESCRIPTIONwb_touch_sensor_enable() allows the user to enable a touch sensor measurement every ms milliseconds. wb_touch_sensor_disable() turns the touch sensor off, saving computation time. NAMEwb_touch_sensor_get_value - get the latest touch sensor measurementC SYNOPSIS#include <webots/touch_sensor.h>double wb_touch_sensor_get_value(WbDeviceTag sensor); C++ SYNOPSIS#include <webots/TouchSensor.hpp>double TouchSensor::getValue(); JAVA SYNOPSISimport com.cyberbotics.webots.controller.TouchSensor;double TouchSensor.getValue(); PYTHON SYNOPSISfrom controller import TouchSensorfloat TouchSensor.getValue() DESCRIPTIONwb_touch_sensor_get_value() returns the last value measured by the specified touch sensor. This value is computed by the simulator according to the lookup table of the TouchSensor node. Hence, the value range for the return value is defined by this lookup table. ![]() ^ page top ^ |
| E-mail to webmaster | Last updated: | Copyright © 2008 Cyberbotics Ltd. |