libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
gripper.h
Go to the documentation of this file.
1// Copyright (c) 2023 Franka Robotics GmbH
2// Use of this source code is governed by the Apache-2.0 license, see LICENSE
3#pragma once
4
5#include <cstdint>
6#include <memory>
7#include <string>
8
10
16namespace franka {
17
18class Network;
19
27class Gripper {
28 public:
32 using ServerVersion = uint16_t;
33
42 explicit Gripper(const std::string& franka_address);
43
49 Gripper(Gripper&& gripper) noexcept;
50
58 Gripper& operator=(Gripper&& gripper) noexcept;
59
63 ~Gripper() noexcept;
64
78 bool homing() const;
79
99 bool grasp(double width,
100 double speed,
101 double force,
102 double epsilon_inner = 0.005,
103 double epsilon_outer = 0.005) const;
104
116 bool move(double width, double speed) const;
117
126 bool stop() const;
127
137
143 ServerVersion serverVersion() const noexcept;
144
146 Gripper(const Gripper&) = delete;
147 Gripper& operator=(const Gripper&) = delete;
149
150 private:
151 std::unique_ptr<Network> network_;
152
153 uint16_t ri_version_;
154};
155
156} // namespace franka
Maintains a network connection to the gripper, provides the current gripper state,...
Definition gripper.h:27
Gripper(const std::string &franka_address)
Establishes a connection with a gripper connected to a robot.
bool move(double width, double speed) const
Moves the gripper fingers to a specified width.
uint16_t ServerVersion
Version of the gripper server.
Definition gripper.h:32
ServerVersion serverVersion() const noexcept
Returns the software version reported by the connected server.
Gripper(Gripper &&gripper) noexcept
Move-constructs a new Gripper instance.
GripperState readOnce() const
Waits for a gripper state update and returns it.
Gripper & operator=(Gripper &&gripper) noexcept
Move-assigns this Gripper from another Gripper instance.
bool grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const
Grasps an object.
bool stop() const
Stops a currently running gripper move or grasp.
~Gripper() noexcept
Closes the connection.
bool homing() const
Performs homing of the gripper.
Contains the franka::GripperState type.
Describes the gripper state.
Definition gripper_state.h:20