libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
grasp_object.cpp

An example showing how to control FRANKA's gripper.

An example showing how to control FRANKA's gripper.

// Copyright (c) 2023 Franka Robotics GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#include <iostream>
#include <sstream>
#include <string>
#include <thread>
#include <franka/gripper.h>
int main(int argc, char** argv) {
if (argc != 4) {
std::cerr << "Usage: ./grasp_object <gripper-hostname> <homing> <object-width>" << std::endl;
return -1;
}
try {
franka::Gripper gripper(argv[1]);
double grasping_width = std::stod(argv[3]);
std::stringstream ss(argv[2]);
bool homing;
if (!(ss >> homing)) {
std::cerr << "<homing> can be 0 or 1." << std::endl;
return -1;
}
if (homing) {
// Do a homing in order to estimate the maximum grasping width with the current fingers.
gripper.homing();
}
// Check for the maximum grasping width.
franka::GripperState gripper_state = gripper.readOnce();
if (gripper_state.max_width < grasping_width) {
std::cout << "Object is too large for the current fingers on the gripper." << std::endl;
return -1;
}
// Grasp the object.
if (!gripper.grasp(grasping_width, 0.1, 60)) {
std::cout << "Failed to grasp object." << std::endl;
return -1;
}
// Wait 3s and check afterwards, if the object is still grasped.
std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(3000));
gripper_state = gripper.readOnce();
if (!gripper_state.is_grasped) {
std::cout << "Object lost." << std::endl;
return -1;
}
std::cout << "Grasped object, will release it now." << std::endl;
gripper.stop();
} catch (franka::Exception const& e) {
std::cout << e.what() << std::endl;
return -1;
}
return 0;
}
Maintains a network connection to the gripper, provides the current gripper state,...
Definition gripper.h:27
GripperState readOnce() const
Waits for a gripper state update and returns it.
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.
bool homing() const
Performs homing of the gripper.
Contains exception definitions.
Contains the franka::Gripper type.
Base class for all exceptions used by libfranka.
Definition exception.h:20
Describes the gripper state.
Definition gripper_state.h:20
bool is_grasped
Indicates whether an object is currently grasped.
Definition gripper_state.h:38
double max_width
Maximum gripper opening width.
Definition gripper_state.h:33