Skip to content

Commit

Permalink
Feature vacuum suction device (#6127)
Browse files Browse the repository at this point in the history
* Add new vacuum suction device

* Synch with webots_ros

* Fix documentation failures

* Fix some issues and add test

* Various fixes

* Fix issues

* Fix ROS server name

* Fix issues

* Synch with webots_ros

* Rename device

* Synch with webots_ros

* Update Makefile

* Update Makefile

* Remove debug changes and fix indentation

* Cleanup

* Remove scale field

* Add contactPoints field

* Adjust sample simulation

* Update WRL file

* Synch webots_ros

* Update docs/reference/vacuumgripper.md

Co-authored-by: Olivier Michel <[email protected]>

* Update docs/reference/vacuumgripper.md

Co-authored-by: Olivier Michel <[email protected]>

* Update lib/controller/python/controller/vacuum_gripper.py

Co-authored-by: Olivier Michel <[email protected]>

* Update Parser.js

* Update documentation

* Connect to the static environment

* Update docs/reference/vacuumgripper.md

Co-authored-by: Olivier Michel <[email protected]>

* Add VacuumGripper to WbConcreteNodeFactory::createCopy

* Remove randomness from controller

* Fix sample world name and use same perspective as other sample worlds

* Improve sample simulation

* Disable slider move

* Improve search for parent solid with physics

* Complete test

* Fix indent

* Add entry in ChangeLog

* Improve search for ODE body

* Fix new method

* Fix ODE include

* Update projects/samples/devices/worlds/vacuum_gripper.wbt

Co-authored-by: Olivier Michel <[email protected]>

---------

Co-authored-by: Olivier Michel <[email protected]>
  • Loading branch information
stefaniapedrazzi and omichel authored Jun 12, 2023
1 parent c7a509c commit eee8e09
Show file tree
Hide file tree
Showing 67 changed files with 2,145 additions and 32 deletions.
1 change: 1 addition & 0 deletions docs/reference/changelog-r2023.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
Released on ??
- New Features
- Added a new [Pose](pose.md) node which inherits from [Group](group.md) and derives to [Transform](transform.md) and [Solid](solid.md) ([#5978](https://github.com/cyberbotics/webots/pull/5978)).
- Added a new [VacuumGripper](vacuumgripper.md) node ([#6127](https://github.com/cyberbotics/webots/pull/6127)).
- Added a new launcher to simplify the start of extern controllers ([#5629](https://github.com/cyberbotics/webots/pull/5629)).
- Added a warning when Webots and controller library versions are different ([#5896](https://github.com/cyberbotics/webots/pull/5896)).
- Added model of the [Husarion](https://husarion.com/)'s ROSbot XL robot and a sample world ([#5973](https://github.com/cyberbotics/webots/pull/5973)).
Expand Down
2 changes: 1 addition & 1 deletion docs/reference/connector.md
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ The default value -1 indicates an infinitely strong docking mechanism that does
This can be used to simulate the rupture of the docking mechanism.
The `shearStrength` field specifies the ability of two connectors to withstand a force that would makes them slide against each other in opposite directions (in the *yz*-plane).
Note that if both connectors are locked, the effective shear strength corresponds to the sum of both connectors' `shearStrength` fields.
The default value -1 indicates an infinitely strong docking mechanism that does not break no matter how much force is applied (in case both connectors are locked, it is sufficient to set the `shearStrength` field of one of the connectors to -1)..
The default value -1 indicates an infinitely strong docking mechanism that does not break no matter how much force is applied (in case both connectors are locked, it is sufficient to set the `shearStrength` field of one of the connectors to -1).

### Connector Axis System

Expand Down
1 change: 1 addition & 0 deletions docs/reference/menu.md
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@
- [Track](track.md)
- [TrackWheel](trackwheel.md)
- [Transform](transform.md)
- [VacuumGripper](vacuumgripper.md)
- [Viewpoint](viewpoint.md)
- [WorldInfo](worldinfo.md)
- [Zoom](zoom.md)
Expand Down
1 change: 1 addition & 0 deletions docs/reference/node-chart.md
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ graph LR
SolidDevice --> Receiver[[Receiver](receiver.md)]
SolidDevice --> Speaker[[Speaker](speaker.md)]
SolidDevice --> TouchSensor[[TouchSensor](touchsensor.md)]
SolidDevice --> VacuumGripper[[VacuumGripper](vacuumgripper.md)]
Solid --> Track[[Track](track.md)]
Solid --> Charger[[Charger](charger.md)]
Solid --> Robot[[Robot](robot.md)]
Expand Down
1 change: 1 addition & 0 deletions docs/reference/nodes-and-api-functions.md
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@
- [Track](track.md)
- [TrackWheel](trackwheel.md)
- [Transform](transform.md)
- [VacuumGripper](vacuumgripper.md)
- [Viewpoint](viewpoint.md)
- [WorldInfo](worldinfo.md)
- [Zoom](zoom.md)
2 changes: 1 addition & 1 deletion docs/reference/nodes-and-keywords.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ In order to describe more precisely robotic simulations, Webots supports additio
These nodes are principally used to model commonly used robot devices.
Here are Webots additional nodes:

`Accelerometer, Altimeter, BallJoint, BallJointParameters, Billboard, Brake, CadShape, Camera, Capsule, Charger, Compass, Connector, ContactProperties, Damping, Display, DistanceSensor, Emitter, Fluid, Focus, GPS, Gyro, HingeJoint, HingeJointParameters, Hinge2Joint, ImmersionProperties, InertialUnit, JointParameters, LED, Lens, LensFlare, Lidar, LightSensor, LinearMotor, Mesh, Muscle, PBRAppearance, Pen, Physics, Plane, PositionSensor, Propeller, Radar, RangeFinder, Receiver, Recognition, Robot, RotationalMotor, Skin, SliderJoint, Slot, Solid, SolidReference, Speaker, Supervisor, TouchSensor, Track, TrackWheel ` and `Zoom`.
`Accelerometer, Altimeter, BallJoint, BallJointParameters, Billboard, Brake, CadShape, Camera, Capsule, Charger, Compass, Connector, ContactProperties, Damping, Display, DistanceSensor, Emitter, Fluid, Focus, GPS, Gyro, HingeJoint, HingeJointParameters, Hinge2Joint, ImmersionProperties, InertialUnit, JointParameters, LED, Lens, LensFlare, Lidar, LightSensor, LinearMotor, Mesh, Muscle, PBRAppearance, Pen, Physics, Plane, PositionSensor, Propeller, Radar, RangeFinder, Receiver, Recognition, Robot, RotationalMotor, Skin, SliderJoint, Slot, Solid, SolidReference, Speaker, Supervisor, TouchSensor, Track, TrackWheel, VacuumGripper, ` and `Zoom`.

Please refer to [this chapter](nodes-and-api-functions.md) for a detailed description of Webots nodes and fields.

Expand Down
2 changes: 1 addition & 1 deletion docs/reference/physics.md
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ But a [Physics](#physics) node can optionally be used if one wishes to simulate
So it is usually recommended to leave the `physics` field of a device empty, unless it represents a significant mass or volume in the simulated robot.
This is true for these devices: [Accelerometer](accelerometer.md), [Altimeter](altimeter.md), [Camera](camera.md), [Compass](compass.md), [DistanceSensor](distancesensor.md), [Emitter](emitter.md), [GPS](gps.md), [LED](led.md), [LightSensor](lightsensor.md), [Pen](pen.md), and [Receiver](receiver.md).

> **Note**: The [InertialUnit](inertialunit.md) and [Connector](connector.md) nodes work differently.
> **Note**: The [InertialUnit](inertialunit.md), [Connector](connector.md), and the [VacuumGripper](vacuumgripper.md) nodes work differently.
Indeed, they require the presence of a [Physics](#physics) node in their parent node to be functional.
It is also possible to specify a [Physics](#physics) node of the device but this adds an extra body to the simulation.

Expand Down
2 changes: 1 addition & 1 deletion docs/reference/solid.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ Solid {
}
```

Direct derived nodes: [Accelerometer](accelerometer.md), [Altimeter](altimeter.md), [Camera](camera.md), [Charger](charger.md), [Compass](compass.md), [Connector](connector.md), [Display](display.md), [DistanceSensor](distancesensor.md), [Emitter](emitter.md), [GPS](gps.md), [Gyro](gyro.md), [InertialUnit](inertialunit.md), [LED](led.md), [Lidar](lidar.md), [LightSensor](lightsensor.md), [Pen](pen.md), [Radar](radar.md), [RangeFinder](rangefinder.md), [Receiver](receiver.md), [Robot](robot.md), [TouchSensor](touchsensor.md), [Track](track.md).
Direct derived nodes: [Accelerometer](accelerometer.md), [Altimeter](altimeter.md), [Camera](camera.md), [Charger](charger.md), [Compass](compass.md), [Connector](connector.md), [Display](display.md), [DistanceSensor](distancesensor.md), [Emitter](emitter.md), [GPS](gps.md), [Gyro](gyro.md), [InertialUnit](inertialunit.md), [LED](led.md), [Lidar](lidar.md), [LightSensor](lightsensor.md), [Pen](pen.md), [Radar](radar.md), [RangeFinder](rangefinder.md), [Receiver](receiver.md), [Robot](robot.md), [TouchSensor](touchsensor.md), [Track](track.md), [VacuumGripper](vacuumgripper.md).

### Description

Expand Down
6 changes: 5 additions & 1 deletion docs/reference/supervisor.md
Original file line number Diff line number Diff line change
Expand Up @@ -358,6 +358,7 @@ typedef enum {
WB_NODE_SKIN,
WB_NODE_SPEAKER,
WB_NODE_TOUCH_SENSOR,
WB_NODE_VACUUM_GRIPPER,
/* misc */
WB_NODE_BALL_JOINT,
WB_NODE_BALL_JOINT_PARAMETERS,
Expand Down Expand Up @@ -414,6 +415,7 @@ namespace webots {
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
// misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
Expand Down Expand Up @@ -451,6 +453,7 @@ class Node:
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
# misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
Expand Down Expand Up @@ -486,6 +489,7 @@ public class Node {
DISTANCE_SENSOR, EMITTER, GPS, GYRO, INERTIAL_UNIT, LED, LIDAR,
LIGHT_SENSOR, LINEAR_MOTOR, PEN, POSITION_SENSOR, PROPELLER,
RADAR, RANGE_FINDER, RECEIVER, ROTATIONAL_MOTOR, SKIN, SPEAKER, TOUCH_SENSOR,
VACUUM_GRIPPER,
// misc
BALL_JOINT, BALL_JOINT_PARAMETERS, CHARGER, CONTACT_PROPERTIES,
DAMPING, FLUID, FOCUS, HINGE_JOINT, HINGE_JOINT_PARAMETERS, HINGE_2_JOINT,
Expand Down Expand Up @@ -523,7 +527,7 @@ WB_NODE_GPS, WB_NODE_GYRO, WB_NODE_INERTIAL_UNIT, WB_NODE_LED, WB_NODE_LIDAR,
WB_NODE_LIGHT_SENSOR, WB_NODE_LINEAR_MOTOR, WB_NODE_PEN,
WB_NODE_POSITION_SENSOR, WB_NODE_PROPELLER, WB_NODE_RADAR,
WB_NODE_RANGE_FINDER, WB_NODE_RECEIVER, WB_NODE_ROTATIONAL_MOTOR,
WB_NODE_SKIN, WB_NODE_SPEAKER, WB_NODE_TOUCH_SENSOR,
WB_NODE_SKIN, WB_NODE_SPEAKER, WB_NODE_TOUCH_SENSOR, WB_NODE_VACUUM_GRIPPER,
% misc
WB_NODE_BALL_JOINT, WB_NODE_BALL_JOINT_PARAMETERS, WB_NODE_CHARGER,
WB_NODE_CONTACT_PROPERTIES, WB_NODE_DAMPING, WB_NODE_FLUID,
Expand Down
252 changes: 252 additions & 0 deletions docs/reference/vacuumgripper.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,252 @@
## Vacuum Gripper

Derived from [Device](device.md) and [Solid](solid.md).

```
VacuumGripper {
SFBool isOn FALSE # {TRUE, FALSE}
SFFloat tensileStrength -1 # {-1, [0, inf)}
SFFloat shearStrength -1 # {-1, [0, inf)}
SFInt32 contactPoints 3 # [1, inf)
}
```

### Description

The [VacuumGripper](#vacuum-gripper) node is used to simulate physical links created by vacuum suction.

The physical connection can be created and destroyed at run time by the robot's controller.
The [VacuumGripper](#vacuum-gripper) node can connect to dynamic [Solid](solid.md) nodes, e.g., for pick and place operations, as well as to the static environment, e.g., for locomotion.
Then, the detection of the presence of an object to connect to is based on collision detection.

### Field Summary

- `isOn`: represents the state of the [VacuumGripper](#vacuum-gripper).
The state can be changed through the `wb_vacuum_gripper_turn_on` and `wb_vacuum_gripper_turn_off` API functions.
The *on state* just means that the suction pump is active, but it does not indicates whether or not an actual physical link exists with an object.
The actual physical link exists only if a valid [Solid](solid.md) object collided with the [VacuumGripper](#vacuum-gripper) after the `wb_vacuum_gripper_turn_on` function was called.

> **Note**:
If the `VacuumGripper` node is on in the .wbt file and a valid [Solid](solid.md) node is available, then the simulation will automatically connect to the [Solid](solid.md) object.
You can take advantage of this feature to start your simulation with the desired mechanical configuration.

- `tensileStrength`: maximum tensile force in *newton* [N] that the suction mechanism can withstand before it breaks.
This can be used to simulate the rupture of the suction mechanism.
The tensile force corresponds to a force that pulls the two objects apart (in the negative *x*-axes direction).
When the tensile force exceeds the tensile strength, the link breaks.
The default value -1 indicates an infinitely strong suction mechanism that does not break no matter how much force is applied.

- `shearStrength`: indicates the maximum shear force in *newtons* [N] that the suction mechanism can withstand before it breaks.
This can be used to simulate the rupture of the suction mechanism.
The `shearStrength` field specifies the ability of the suction mechanism to withstand a force that would makes them slide against each other in opposite directions (in the *yz*-plane).
The default value -1 indicates an infinitely strong suction mechanism that does not break no matter how much force is applied.

- `contactPoints`: indicates the minimum number of contact points with the [Solid](solid.md) object required to connect.


### VacuumGripper Functions

#### `wb_vacuum_gripper_enable_presence`
#### `wb_vacuum_gripper_disable_presence`
#### `wb_vacuum_gripper_get_presence_sampling_period`
#### `wb_vacuum_gripper_get_presence`

%tab-component "language"

%tab "C"

```c
#include <webots/vacuum_gripper.h>

void wb_vacuum_gripper_enable_presence(WbDeviceTag tag, int sampling_period);
void wb_vacuum_gripper_disable_presence(WbDeviceTag tag);
int wb_vacuum_gripper_get_presence_sampling_period(WbDeviceTag tag);
bool wb_vacuum_gripper_get_presence(WbDeviceTag tag);
```
%tab-end
%tab "C++"
```cpp
#include <webots/VacuumGripper.hpp>
namespace webots {
class VacuumGripper : public Device {
virtual void enablePresence(int samplingPeriod);
virtual void disablePresence();
int getPresenceSamplingPeriod() const;
bool getPresence() const;
// ...
}
}
```

%tab-end

%tab "Python"

```python
from controller import VacuumGripper

class VacuumGripper (Device):
def enablePresence(self, samplingPeriod):
def disablePresence(self):
def getPresenceSamplingPeriod(self):
def getPresence(self):
# ...
```

%tab-end

%tab "Java"

```java
import com.cyberbotics.webots.controller.VacuumGripper;

public class VacuumGripper extends Device {
public void enablePresence(int samplingPeriod);
public void disablePresence();
public int getPresenceSamplingPeriod();
public boolean getPresence();
// ...
}
```

%tab-end

%tab "MATLAB"

```MATLAB
wb_vacuum_gripper_enable_presence(tag, sampling_period)
wb_vacuum_gripper_disable_presence(tag)
period = wb_vacuum_gripper_get_presence_sampling_period(tag)
presence = wb_vacuum_gripper_get_presence(tag)
```

%tab-end

%tab "ROS"

| name | service/topic | data type | data type definition |
| --- | --- | --- | --- |
| `/<device_name>/presence` | `topic` | `webots_ros::BoolStamped` | [`Header`](http://docs.ros.org/api/std_msgs/html/msg/Header.html) `header`<br/>`bool data` |
| `/<device_name>/presence_sensor/enable` | `service` | [`webots_ros::set_int`](ros-api.md#common-services) | |
| `/<device_name>/presence_sensor/get_sampling_period` | `service` | [`webots_ros::get_int`](ros-api.md#common-services) | |

%tab-end

%end

##### Description

*detect the presence of a connected object*

The `wb_vacuum_gripper_enable_presence` function starts querying the presence of a linked [Solid](solid.md) object.
The `sampling_period` argument specifies the sampling period of the presence sensor.
It is expressed in milliseconds.
Note that it will be active only after the first sampling period elapsed.

The `wb_vacuum_gripper_disable_presence` function stops querying the presence sensor of a linked [Solid](solid.md) object.

The `wb_vacuum_gripper_get_presence_sampling_period` function returns the period at which the presence sensor of the linked [Solid](solid.md) object is queried.
The `wb_vacuum_gripper_get_presence` function returns the current *presence* state, it returns *TRUE* if a [Solid](solid.md) object is connected and *FALSE* otherwise.

---

#### `wb_vacuum_gripper_turn_on`
#### `wb_vacuum_gripper_turn_off`
#### `wb_vacuum_gripper_is_on`

%tab-component "language"

%tab "C"

```c
#include <webots/vacuum_gripper.h>

void wb_vacuum_gripper_turn_on(WbDeviceTag tag);
void wb_vacuum_gripper_turn_off(WbDeviceTag tag);
bool wb_vacuum_gripper_is_on(WbDeviceTag tag);
```
%tab-end
%tab "C++"
```cpp
#include <webots/VacuumGripper.hpp>
namespace webots {
class VacuumGripper : public Device {
virtual void turnOn();
virtual void turnOff();
virtual bool isOn()
// ...
}
}
```

%tab-end

%tab "Python"

```python
from controller import VacuumGripper

class VacuumGripper (Device):
def turnOn(self):
def turnOff(self):
def isOn(self):
# ...
```

%tab-end

%tab "Java"

```java
import com.cyberbotics.webots.controller.VacuumGripper;

public class VacuumGripper extends Device {
public void turnOn();
public void turnOff();
public boolean isOn();
// ...
}
```

%tab-end

%tab "MATLAB"

```MATLAB
wb_vacuum_gripper_turn_on(tag)
wb_vacuum_gripper_turn_off(tag)
on = wb_vacuum_gripper_is_on(tag)
```

%tab-end

%tab "ROS"

| name | service/topic | data type | data type definition |
| --- | --- | --- | --- |
| `/<device_name>/turn_on` | `service` | [`webots_ros::set_bool`](ros-api.md#common-services) | |
| `/<device_name>/is_on` | `service` | [`webots_ros::get_bool`](ros-api.md#common-services) | |

%tab-end

%end

##### Description

*create / destroy the physical connection wit a solid object*

The `wb_vacuum_gripper_turn_on` and `wb_vacuum_gripper_turn_off` functions can be used to activate or deactivate the [VacuumGripper](#vacuum-gripper) suction pump and changing the status of the `isOn` field.
This will eventually create or destroy the physical connection with a [Solid](solid.md) object.

If dynamic [Solid](solid.md) object collides with the [VacuumGripper](#vacuum-gripper) while the device is on, a physical link will be created between the [VacuumGripper](#vacuum-gripper) and the [Solid](solid.md) object.
The two connected bodies will then keep a constant distance and orientation with respect to each other from this moment on.

If the `wb_vacuum_gripper_turn_off` function is invoked while there is a physical link between the [VacuumGripper](#vacuum-gripper) and a [Solid](solid.md) object, the link will be destroyed.
1 change: 1 addition & 0 deletions include/controller/c/webots/nodes.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ typedef enum {
WB_NODE_SKIN,
WB_NODE_SPEAKER,
WB_NODE_TOUCH_SENSOR,
WB_NODE_VACUUM_GRIPPER,
// misc
WB_NODE_BALL_JOINT,
WB_NODE_BALL_JOINT_PARAMETERS,
Expand Down
Loading

0 comments on commit eee8e09

Please sign in to comment.