12 #include <spdlog/spdlog.h>
19 using namespace flexiv;
23 std::atomic<bool> g_finished = {
false};
30 std::cout <<
"Required arguments: [robot_sn] [gripper_name]" << std::endl;
31 std::cout <<
" robot_sn: Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456" << std::endl;
32 std::cout <<
" gripper_name: Full name of the gripper to be controlled, can be found in Flexiv Elements -> Settings -> Device" << std::endl;
33 std::cout <<
"Optional arguments: None" << std::endl;
34 std::cout << std::endl;
43 spdlog::info(
"Current gripper states:");
44 std::cout << gripper.
states() << std::endl;
45 std::this_thread::sleep_for(std::chrono::seconds(1));
49 int main(
int argc,
char* argv[])
54 if (argc < 3 || rdk::utility::ProgramArgsExistAny(argc, argv, {
"-h",
"--help"})) {
59 std::string robot_sn = argv[1];
60 std::string gripper_name = argv[2];
64 ">>> Tutorial description <<<\nThis tutorial does position and force (if available) "
65 "control of grippers supported by Flexiv.\n");
75 spdlog::warn(
"Fault occurred on the connected robot, trying to clear ...");
77 if (!robot.ClearFault()) {
78 spdlog::error(
"Fault cannot be cleared, exiting ...");
81 spdlog::info(
"Fault on the connected robot is cleared");
85 spdlog::info(
"Enabling robot ...");
89 while (!robot.operational()) {
90 std::this_thread::sleep_for(std::chrono::seconds(1));
92 spdlog::info(
"Robot is now operational");
106 spdlog::info(
"Enabling gripper [{}]", gripper_name);
107 gripper.
Enable(gripper_name);
110 spdlog::info(
"Gripper params:");
111 std::cout << std::fixed << std::setprecision(3) <<
"{\n"
118 <<
"\nmax_vel: " << gripper.
params().
max_vel <<
"\n}" << std::endl;
121 spdlog::info(
"Switching robot tool to [{}]", gripper_name);
122 tool.Switch(gripper_name);
127 "Manually trigger initialization for the gripper now? Choose Yes if it's a 48v Grav "
129 std::cout <<
"[1] No, it has already initialized automatically when power on" << std::endl;
130 std::cout <<
"[2] Yes, it does not initialize itself when power on" << std::endl;
135 spdlog::info(
"Skipped manual initialization");
136 }
else if (choice == 2) {
140 "Triggered manual initialization, press Enter when the initialization is finished "
145 spdlog::error(
"Invalid choice");
150 std::thread print_thread(PrintGripperStates, std::ref(gripper));
153 spdlog::info(
"Closing gripper");
154 gripper.
Move(0.01, 0.1, 20);
155 std::this_thread::sleep_for(std::chrono::seconds(2));
156 spdlog::info(
"Opening gripper");
157 gripper.
Move(0.09, 0.1, 20);
158 std::this_thread::sleep_for(std::chrono::seconds(2));
161 spdlog::info(
"Closing gripper");
162 gripper.
Move(0.01, 0.1, 20);
163 std::this_thread::sleep_for(std::chrono::milliseconds(500));
164 spdlog::info(
"Stopping gripper");
166 std::this_thread::sleep_for(std::chrono::seconds(2));
167 spdlog::info(
"Closing gripper");
168 gripper.
Move(0.01, 0.1, 20);
169 std::this_thread::sleep_for(std::chrono::seconds(2));
170 spdlog::info(
"Opening gripper");
171 gripper.
Move(0.09, 0.1, 20);
172 std::this_thread::sleep_for(std::chrono::milliseconds(500));
173 spdlog::info(
"Stopping gripper");
175 std::this_thread::sleep_for(std::chrono::seconds(2));
178 if (fabs(gripper.
states().
force) > std::numeric_limits<double>::epsilon()) {
179 spdlog::info(
"Gripper running zero force control");
182 std::this_thread::sleep_for(std::chrono::seconds(10));
188 spdlog::info(
"Program finished");
191 }
catch (
const std::exception& e) {
192 spdlog::error(e.what());
Interface with the robot gripper. Because gripper is also a type of device, this API uses the same un...
const GripperStates states() const
[Non-blocking] Current states data of the enabled gripper.
void Stop()
[Blocking] Stop the gripper and hold its current finger width.
void Move(double width, double velocity, double force_limit=0)
[Blocking] Move the gripper fingers with position control.
void Init()
[Blocking] Manually trigger the initialization of the enabled gripper. This step is not needed for gr...
const GripperParams params() const
[Non-blocking] Parameters of the currently enabled gripper.
void Enable(const std::string &name)
[Blocking] Enable the specified gripper as a device, same as Device::Enable().
void Grasp(double force)
[Blocking] Grasp with direct force control. Requires the mounted gripper to support direct force cont...
Main interface with the robot, containing several function categories and background services.