This tutorial does position and force (if available) control of grippers supported by Flexiv.
#include <spdlog/spdlog.h>
#include <iostream>
#include <iomanip>
#include <thread>
#include <atomic>
using namespace flexiv;
namespace {
std::atomic<bool> g_finished = {false};
}
void PrintHelp()
{
std::cout << "Required arguments: [robot_sn] [gripper_name]" << std::endl;
std::cout << " robot_sn: Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456" << std::endl;
std::cout << " gripper_name: Full name of the gripper to be controlled, can be found in Flexiv Elements -> Settings -> Device" << std::endl;
std::cout << "Optional arguments: None" << std::endl;
std::cout << std::endl;
}
void PrintGripperStates(rdk::Gripper& gripper)
{
while (!g_finished) {
spdlog::info("Current gripper states:");
std::cout << gripper.states() << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
}
}
int main(int argc, char* argv[])
{
if (argc < 3 ||
rdk::utility::ProgramArgsExistAny(argc, argv, {
"-h",
"--help"})) {
PrintHelp();
return 1;
}
std::string robot_sn = argv[1];
std::string gripper_name = argv[2];
spdlog::info(
">>> Tutorial description <<<\nThis tutorial does position and force (if available) "
"control of grippers supported by Flexiv.\n");
try {
rdk::Robot robot(robot_sn);
if (robot.fault()) {
spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
if (!robot.ClearFault()) {
spdlog::error("Fault cannot be cleared, exiting ...");
return 1;
}
spdlog::info("Fault on the connected robot is cleared");
}
spdlog::info("Enabling robot ...");
robot.Enable();
while (!robot.operational()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
spdlog::info("Robot is now operational");
rdk::Gripper gripper(robot);
rdk::Tool tool(robot);
spdlog::info("Enabling gripper [{}]", gripper_name);
gripper.Enable(gripper_name);
spdlog::info("Gripper params:");
std::cout << std::fixed << std::setprecision(3) << "{\n"
<< "name: " << gripper.params().name
<< "\nmin_width: " << gripper.params().min_width
<< "\nmax_width: " << gripper.params().max_width
<< "\nmin_force: " << gripper.params().min_force
<< "\nmax_force: " << gripper.params().max_force
<< "\nmin_vel: " << gripper.params().min_vel
<< "\nmax_vel: " << gripper.params().max_vel << "\n}" << std::endl;
spdlog::info("Switching robot tool to [{}]", gripper_name);
tool.Switch(gripper_name);
int choice = 0;
spdlog::info(
"Manually trigger initialization for the gripper now? Choose Yes if it's a 48v Grav "
"gripper");
std::cout << "[1] No, it has already initialized automatically when power on" << std::endl;
std::cout << "[2] Yes, it does not initialize itself when power on" << std::endl;
std::cin >> choice;
if (choice == 1) {
spdlog::info("Skipped manual initialization");
} else if (choice == 2) {
gripper.Init();
spdlog::info(
"Triggered manual initialization, press Enter when the initialization is finished "
"to continue");
std::cin.get();
std::cin.get();
} else {
spdlog::error("Invalid choice");
return 1;
}
std::thread print_thread(PrintGripperStates, std::ref(gripper));
spdlog::info("Closing gripper");
gripper.Move(0.01, 0.1, 20);
std::this_thread::sleep_for(std::chrono::seconds(2));
spdlog::info("Opening gripper");
gripper.Move(0.09, 0.1, 20);
std::this_thread::sleep_for(std::chrono::seconds(2));
spdlog::info("Closing gripper");
gripper.Move(0.01, 0.1, 20);
std::this_thread::sleep_for(std::chrono::milliseconds(500));
spdlog::info("Stopping gripper");
gripper.Stop();
std::this_thread::sleep_for(std::chrono::seconds(2));
spdlog::info("Closing gripper");
gripper.Move(0.01, 0.1, 20);
std::this_thread::sleep_for(std::chrono::seconds(2));
spdlog::info("Opening gripper");
gripper.Move(0.09, 0.1, 20);
std::this_thread::sleep_for(std::chrono::milliseconds(500));
spdlog::info("Stopping gripper");
gripper.Stop();
std::this_thread::sleep_for(std::chrono::seconds(2));
if (fabs(gripper.states().force) > std::numeric_limits<double>::epsilon()) {
spdlog::info("Gripper running zero force control");
gripper.Grasp(0);
std::this_thread::sleep_for(std::chrono::seconds(10));
}
gripper.Stop();
g_finished = true;
spdlog::info("Program finished");
print_thread.join();
} catch (const std::exception& e) {
spdlog::error(e.what());
return 1;
}
return 0;
}