libfranka  0.8.0
FCI C++ API
Public Attributes | List of all members
franka::GripperState Struct Reference

Describes the gripper state. More...

#include <gripper_state.h>

Collaboration diagram for franka::GripperState:
Collaboration graph
[legend]

Public Attributes

double width {}
 Current gripper opening width. More...
 
double max_width {}
 Maximum gripper opening width. More...
 
bool is_grasped {}
 Indicates whether an object is currently grasped.
 
uint16_t temperature {}
 Current gripper temperature. More...
 
Duration time {}
 Strictly monotonically increasing timestamp since robot start.
 

Detailed Description

Describes the gripper state.

Examples:
grasp_object.cpp.

Member Data Documentation

◆ max_width

double franka::GripperState::max_width {}

Maximum gripper opening width.

This parameter is estimated by homing the gripper. After changing the gripper fingers, a homing needs to be done. Unit: \([m]\).

See also
Gripper::homing.
Examples:
grasp_object.cpp.

◆ temperature

uint16_t franka::GripperState::temperature {}

Current gripper temperature.

Unit: \([°C]\).

◆ width

double franka::GripperState::width {}

Current gripper opening width.

Unit: \([m]\).


The documentation for this struct was generated from the following file: