libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
vacuum_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 <chrono>
6#include <cstdint>
7#include <memory>
8#include <string>
9
11
17namespace franka {
18
19class Network;
20
29 public:
33 using ServerVersion = uint16_t;
34
38 enum class ProductionSetupProfile { kP0, kP1, kP2, kP3 };
39
48 explicit VacuumGripper(const std::string& franka_address);
49
55 VacuumGripper(VacuumGripper&& vacuum_gripper) noexcept;
56
64 VacuumGripper& operator=(VacuumGripper&& vacuum_gripper) noexcept;
65
69 ~VacuumGripper() noexcept;
70
83 bool vacuum(uint8_t vacuum,
84 std::chrono::milliseconds timeout,
86
97 bool dropOff(std::chrono::milliseconds timeout) const;
98
107 bool stop() const;
108
118
124 ServerVersion serverVersion() const noexcept;
125
127 VacuumGripper(const VacuumGripper&) = delete;
128 VacuumGripper& operator=(const VacuumGripper&) = delete;
130
131 private:
132 std::unique_ptr<Network> network_;
133
134 uint16_t ri_version_;
135};
136
137} // namespace franka
Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state,...
Definition vacuum_gripper.h:28
bool dropOff(std::chrono::milliseconds timeout) const
Drops the grasped object off.
ProductionSetupProfile
Vacuum production setup profile.
Definition vacuum_gripper.h:38
ServerVersion serverVersion() const noexcept
Returns the software version reported by the connected server.
bool stop() const
Stops a currently running vacuum gripper vacuum or drop off operation.
bool vacuum(uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const
Vacuums an object.
uint16_t ServerVersion
Version of the vacuum gripper server.
Definition vacuum_gripper.h:33
VacuumGripper & operator=(VacuumGripper &&vacuum_gripper) noexcept
Move-assigns this VacuumGripper from another VacuumGripper instance.
VacuumGripperState readOnce() const
Waits for a vacuum gripper state update and returns it.
VacuumGripper(const std::string &franka_address)
Establishes a connection with a vacuum gripper connected to a robot.
VacuumGripper(VacuumGripper &&vacuum_gripper) noexcept
Move-constructs a new VacuumGripper instance.
~VacuumGripper() noexcept
Closes the connection.
Describes the vacuum gripper state.
Definition vacuum_gripper_state.h:31
Contains the franka::VacuumGripperState type.