Webots Reference Manual

previous page go up next page

Thanks

1. Introduction

2. Node Chart

3. Nodes and API Functions

4. Motion Functions

5. Prototypes

6. Physics Plugin

7. Fast2D Plugin

8. MTN Functions

9. Webots World Files

     

3.21 Gripper

Derived from Solid.

Gripper {
  SFFloat   position   0
}

3.21.1 Description

The Gripper node models a simple gripper system with two fingers capable of grasping small objects (typically vertical cylinders), moving them around and releasing them. This device should only be used in simple kinematic-based simulations (without Physics nodes). It provides a very fast simulation of a simple gripper device as opposed to the equivalent physics-based simulation. For more complex gripper usages, you should implement a physics-based simulation (i.e., with Physics nodes) including two Servo devices, each one being a finger of the gripper.

The khepera_gripper.wbt file provides an example of a robot using such a simple gripper system in a kinematic-based simulation (located in the projects/robots/khepera/worlds directory of Webots).

To be operational, a Gripper node must contain two Solid nodes as children. These Solid nodes should be named "left grip" and "right grip" (name field). They correspond to the fingers of the gripper. Each of these Solid nodes should have a properly defined boundingObject field. As shown in the khepera_gripper.wbt example, the Gripper node can be mounted on the top of a Servo node acting like an arm. Moreover, distance sensors or other sensor types can be mounted on the fingers of the gripper.

3.21.2 Field Summary

  • The position field corresponds to the aperture of the gripper. It is expressed in meters. By default, this value is 0 (gripper is closed).

3.21.3 Gripper Functions

NAME

   wb_gripper_set_position - open or close the gripper

C SYNOPSIS

  #include <webots/gripper.h>

  void wb_gripper_set_position(WbDeviceTag gripper, double position);

C++ SYNOPSIS

  #include <webots/Gripper.hpp>

  void Gripper::setPosition(double position);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Gripper;

  void Gripper.setPosition(double position);

PYTHON SYNOPSIS

  from controller import Gripper

  none Gripper.setPosition(float position)

DESCRIPTION

The wb_gripper_set_position() function allows the user to close or open the gripper depending on the specified position value, which represents the aperture of the gripper device expressed in meters. Hence a value of 0 will close the gripper and a value of 0.04 will open the gripper 4 cm wide.

NAME

   wb_gripper_enable_position, wb_gripper_disable_position, wb_gripper_get_position - enable, disable and return the current state of the position sensor on a gripper

C SYNOPSIS

  #include <webots/gripper.h>

  void wb_gripper_enable_position(WbDeviceTag gripper, int ms);
  void wb_gripper_disable_position(WbDeviceTag gripper);
  double wb_gripper_get_position(WbDeviceTag gripper);

C++ SYNOPSIS

  #include <webots/Gripper.hpp>

  void Gripper::enablePosition(int ms);
  void Gripper::disablePosition();
  double Gripper::getPosition();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Gripper;

  void Gripper.enablePosition(int ms);
  void Gripper.disablePosition();
  double Gripper.getPosition();

PYTHON SYNOPSIS

  from controller import Gripper

  none Gripper.enablePosition(int ms)
  none Gripper.disablePosition()
  float Gripper.getPosition()

DESCRIPTION

The wb_gripper_enable_position() function starts gripper position measurements each ms milliseconds. The wb_gripper_disable_position() function stops the gripper position measurements.

The wb_gripper_get_position() function returns the position measurement of the specified gripper device. The position is expressed in meters, and corresponds to the aperture of the gripper (as with the wb_gripper_set_position() function). However, it returns the current position of the gripper, and not the target position specified with wb_gripper_set_position() (which may be the same value when the target position is reached). This function may be useful to measure the size of a gripped object.

NAME

   wb_gripper_enable_resistivity, wb_gripper_disable_resistivity, wb_gripper_get_resistivity - perform resistivity measurements on a gripper

C SYNOPSIS

  #include <webots/gripper.h>

  void wb_gripper_enable_resistivity(WbDeviceTag gripper, int ms);
  void wb_gripper_disable_resistivity(WbDeviceTag gripper);
  double wb_gripper_get_resistivity(WbDeviceTag gripper);

C++ SYNOPSIS

  #include <webots/Gripper.hpp>

  void Gripper::enableResistivity(int ms);
  void Gripper::disableResistivity();
  double Gripper::getResistivity();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Gripper;

  void Gripper.enableResistivity(int ms);
  void Gripper.disableResistivity();
  double Gripper.getResistivity();

PYTHON SYNOPSIS

  from controller import Gripper

  none Gripper.enableResistivity(int ms)
  none Gripper.disableResistivity()
  float Gripper.getResistivity()

DESCRIPTION

The wb_gripper_enable_resistivity() function enables gripper resistivity measurements each ms milliseconds. The wb_gripper_disable_resistivity() function stops the gripper resistivity measurements.

The wb_gripper_get_resistivity() function returns the resistivity measurement performed on the specified gripper device. This value is expressed in Ohms. The current version of Webots assumes that any object has a resistivity of one Ohm. It will return Inf when no object is gripped and 1.0 when an object is gripped.

previous page go up next page
^ page top ^

  E-mail to webmaster Last updated: Copyright © 2008 Cyberbotics Ltd.