Flexiv RDK APIs  1.6.0
basics6_gripper_control.cpp
1 
8 #include <flexiv/rdk/robot.hpp>
9 #include <flexiv/rdk/gripper.hpp>
10 #include <flexiv/rdk/tool.hpp>
11 #include <flexiv/rdk/utility.hpp>
12 #include <spdlog/spdlog.h>
13 
14 #include <iostream>
15 #include <iomanip>
16 #include <thread>
17 #include <atomic>
18 
19 using namespace flexiv;
20 
21 namespace {
23 std::atomic<bool> g_finished = {false};
24 }
25 
27 void PrintHelp()
28 {
29  // clang-format off
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;
35  // clang-format on
36 }
37 
39 void PrintGripperStates(rdk::Gripper& gripper)
40 {
41  while (!g_finished) {
42  // Print all gripper states in JSON format using the built-in ostream operator overloading
43  spdlog::info("Current gripper states:");
44  std::cout << gripper.states() << std::endl;
45  std::this_thread::sleep_for(std::chrono::seconds(1));
46  }
47 }
48 
49 int main(int argc, char* argv[])
50 {
51  // Program Setup
52  // =============================================================================================
53  // Parse parameters
54  if (argc < 3 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
55  PrintHelp();
56  return 1;
57  }
58  // Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456
59  std::string robot_sn = argv[1];
60  std::string gripper_name = argv[2];
61 
62  // Print description
63  spdlog::info(
64  ">>> Tutorial description <<<\nThis tutorial does position and force (if available) "
65  "control of grippers supported by Flexiv.\n");
66 
67  try {
68  // RDK Initialization
69  // =========================================================================================
70  // Instantiate robot interface
71  rdk::Robot robot(robot_sn);
72 
73  // Clear fault on the connected robot if any
74  if (robot.fault()) {
75  spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
76  // Try to clear the fault
77  if (!robot.ClearFault()) {
78  spdlog::error("Fault cannot be cleared, exiting ...");
79  return 1;
80  }
81  spdlog::info("Fault on the connected robot is cleared");
82  }
83 
84  // Enable the robot, make sure the E-Stop is released before enabling
85  spdlog::info("Enabling robot ...");
86  robot.Enable();
87 
88  // Wait for the robot to become operational
89  while (!robot.operational()) {
90  std::this_thread::sleep_for(std::chrono::seconds(1));
91  }
92  spdlog::info("Robot is now operational");
93 
94  // Gripper Control
95  // =========================================================================================
96  // Instantiate gripper control interface
97  rdk::Gripper gripper(robot);
98 
99  // Instantiate tool interface. Gripper is categorized as both a device and a tool. The
100  // device attribute allows a gripper to be interactively controlled by the user; whereas the
101  // tool attribute tells the robot to account for its mass properties and TCP location.
102  rdk::Tool tool(robot);
103 
104  // Enable the specified gripper as a device. This is equivalent to enabling the specified
105  // gripper in Flexiv Elements -> Settings -> Device
106  spdlog::info("Enabling gripper [{}]", gripper_name);
107  gripper.Enable(gripper_name);
108 
109  // Print parameters of the enabled gripper
110  spdlog::info("Gripper params:");
111  std::cout << std::fixed << std::setprecision(3) << "{\n"
112  << "name: " << gripper.params().name
113  << "\nmin_width: " << gripper.params().min_width
114  << "\nmax_width: " << gripper.params().max_width
115  << "\nmin_force: " << gripper.params().min_force
116  << "\nmax_force: " << gripper.params().max_force
117  << "\nmin_vel: " << gripper.params().min_vel
118  << "\nmax_vel: " << gripper.params().max_vel << "\n}" << std::endl;
119 
120  // Switch robot tool to gripper so the gravity compensation and TCP location is updated
121  spdlog::info("Switching robot tool to [{}]", gripper_name);
122  tool.Switch(gripper_name);
123 
124  // User needs to determine if this gripper requires manual initialization
125  int choice = 0;
126  spdlog::info(
127  "Manually trigger initialization for the gripper now? Choose Yes if it's a 48v Grav "
128  "gripper");
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;
131  std::cin >> choice;
132 
133  // Trigger manual initialization based on choice
134  if (choice == 1) {
135  spdlog::info("Skipped manual initialization");
136  } else if (choice == 2) {
137  gripper.Init();
138  // User determines if the manual initialization is finished
139  spdlog::info(
140  "Triggered manual initialization, press Enter when the initialization is finished "
141  "to continue");
142  std::cin.get();
143  std::cin.get();
144  } else {
145  spdlog::error("Invalid choice");
146  return 1;
147  }
148 
149  // Start a separate thread to print gripper states
150  std::thread print_thread(PrintGripperStates, std::ref(gripper));
151 
152  // Position control
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));
159 
160  // Stop
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");
165  gripper.Stop();
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");
174  gripper.Stop();
175  std::this_thread::sleep_for(std::chrono::seconds(2));
176 
177  // Force control, if available (sensed force is not zero)
178  if (fabs(gripper.states().force) > std::numeric_limits<double>::epsilon()) {
179  spdlog::info("Gripper running zero force control");
180  gripper.Grasp(0);
181  // Exit after 10 seconds
182  std::this_thread::sleep_for(std::chrono::seconds(10));
183  }
184 
185  // Finished, exit all threads
186  gripper.Stop();
187  g_finished = true;
188  spdlog::info("Program finished");
189  print_thread.join();
190 
191  } catch (const std::exception& e) {
192  spdlog::error(e.what());
193  return 1;
194  }
195 
196  return 0;
197 }
Interface with the robot gripper. Because gripper is also a type of device, this API uses the same un...
Definition: gripper.hpp:78
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.
Definition: robot.hpp:25
Interface to online update and interact with the robot tools. All updates will take effect immediatel...
Definition: tool.hpp:42