Flexiv RDK APIs  1.6.0
basics3_primitive_execution.cpp
1 
9 #include <flexiv/rdk/robot.hpp>
10 #include <flexiv/rdk/utility.hpp>
11 #include <spdlog/spdlog.h>
12 
13 #include <iostream>
14 #include <iomanip>
15 #include <thread>
16 
17 using namespace flexiv;
18 
20 void PrintHelp()
21 {
22  // clang-format off
23  std::cout << "Required arguments: [robot_sn]" << std::endl;
24  std::cout << " robot_sn: Serial number of the robot to connect. Remove any space, e.g. Rizon4s-123456" << std::endl;
25  std::cout << "Optional arguments: None" << std::endl;
26  std::cout << std::endl;
27  // clang-format on
28 }
29 
30 int main(int argc, char* argv[])
31 {
32  // Program Setup
33  // =============================================================================================
34  // Parse parameters
35  if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
36  PrintHelp();
37  return 1;
38  }
39  // Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456
40  std::string robot_sn = argv[1];
41 
42  // Print description
43  spdlog::info(
44  ">>> Tutorial description <<<\nThis tutorial executes several basic robot primitives (unit "
45  "skills). For detailed documentation on all available primitives, please see [Flexiv "
46  "Primitives](https://www.flexiv.com/primitives/).\n");
47 
48  try {
49  // RDK Initialization
50  // =========================================================================================
51  // Instantiate robot interface
52  rdk::Robot robot(robot_sn);
53 
54  // Clear fault on the connected robot if any
55  if (robot.fault()) {
56  spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
57  // Try to clear the fault
58  if (!robot.ClearFault()) {
59  spdlog::error("Fault cannot be cleared, exiting ...");
60  return 1;
61  }
62  spdlog::info("Fault on the connected robot is cleared");
63  }
64 
65  // Enable the robot, make sure the E-stop is released before enabling
66  spdlog::info("Enabling robot ...");
67  robot.Enable();
68 
69  // Wait for the robot to become operational
70  while (!robot.operational()) {
71  std::this_thread::sleep_for(std::chrono::seconds(1));
72  }
73  spdlog::info("Robot is now operational");
74 
75  // Execute Primitives
76  // =========================================================================================
77  // Switch to primitive execution mode
78  robot.SwitchMode(rdk::Mode::NRT_PRIMITIVE_EXECUTION);
79 
80  // (1) Go to home pose
81  // -----------------------------------------------------------------------------------------
82  // All parameters of the "Home" primitive are optional, thus we can skip the parameters and
83  // the default values will be used
84  spdlog::info("Executing primitive: Home");
85 
86  // Send command to robot
87  robot.ExecutePrimitive("Home", std::map<std::string, rdk::FlexivDataTypes> {});
88 
89  // Wait for reached target
90  while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
91  std::this_thread::sleep_for(std::chrono::seconds(1));
92  }
93 
94  // (2) Move robot joints to target positions
95  // -----------------------------------------------------------------------------------------
96  // Required parameters:
97  // target: final joint positions, unit: degrees
98  // {arm joint positions}, {external axis joint positions}
99  // Optional parameters:
100  // waypoints: waypoints to pass before reaching the target
101  // (same format as above, but can be more than one)
102  // vel: TCP linear velocity, unit: m/s
103  // Optional properties:
104  // lockExternalAxes: whether to allow the external axes to move or not
105  spdlog::info("Executing primitive: MoveJ");
106 
107  // Send command to robot
108  robot.ExecutePrimitive("MoveJ",
109  {
110  {"target", rdk::JPos({30, -45, 0, 90, 0, 40, 30}, {-50, 30})},
111  {"waypoints",
112  std::vector<rdk::JPos> {rdk::JPos({10, -30, 10, 30, 10, 15, 10}, {-15, 10}),
113  rdk::JPos({20, -60, -10, 60, -10, 30, 20}, {-30, 20})}},
114  },
115  {
116  {"lockExternalAxes", 0},
117  });
118 
119  // Most primitives won't exit by themselves and require users to explicitly trigger
120  // transitions based on specific primitive states. Here we check if the primitive state
121  // [reachedTarget] becomes true and trigger the transition manually by sending a new
122  // primitive command.
123  while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
124  // Print current primitive states
125  spdlog::info("Current primitive states:");
126  for (const auto& st : robot.primitive_states()) {
127  std::cout << st.first << ": " << rdk::utility::FlexivTypes2Str(st.second);
128  std::cout << std::endl;
129  }
130  std::this_thread::sleep_for(std::chrono::seconds(1));
131  }
132 
133  // (3) Move robot TCP to a target pose in world (base) frame
134  // -----------------------------------------------------------------------------------------
135  // Required parameters:
136  // target: final TCP pose, unit: m and degrees
137  // {pos_x, pos_y, pos_z}, {rot_x, rot_y, rot_z}, {ref_frame, ref_point}
138  // Optional parameters:
139  // waypoints: waypoints to pass before reaching the target
140  // (same format as above, but can be more than one)
141  // vel: TCP linear velocity, unit: m/s
142  // NOTE: The rotations use Euler ZYX convention, rot_x means Euler ZYX angle around X axis
143  spdlog::info("Executing primitive: MoveL");
144 
145  // Send command to robot
146  robot.ExecutePrimitive("MoveL",
147  {
148  {"target", rdk::Coord({0.65, -0.3, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"})},
149  {"waypoints",
150  std::vector<rdk::Coord> {
151  rdk::Coord({0.45, 0.1, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"}),
152  rdk::Coord({0.45, -0.3, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"})}},
153  {"vel", 0.6},
154  {"zoneRadius", "Z50"},
155  });
156 
157  // Wait for reached target
158  while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
159  std::this_thread::sleep_for(std::chrono::seconds(1));
160  }
161 
162  // (4) Another MoveL that uses TCP frame
163  // -----------------------------------------------------------------------------------------
164  // In this example the reference frame is changed from WORLD::WORLD_ORIGIN to TRAJ::START,
165  // which represents the current TCP frame
166  spdlog::info("Executing primitive: MoveL");
167 
168  // Example to convert target quaternion [w,x,y,z] to Euler ZYX using utility functions
169  std::array<double, 4> targetQuat = {0.9185587, 0.1767767, 0.3061862, 0.1767767};
170  // ZYX = [30, 30, 30] degrees
171  auto targetEulerDeg = rdk::utility::Rad2Deg(rdk::utility::Quat2EulerZYX(targetQuat));
172 
173  // Send command to robot. This motion will hold current TCP position and only do rotation
174  robot.ExecutePrimitive(
175  "MoveL", {
176  {"target", rdk::Coord({0.0, 0.0, 0.0}, targetEulerDeg, {"TRAJ", "START"})},
177  {"vel", 0.2},
178  });
179  // Wait for reached target
180  while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
181  std::this_thread::sleep_for(std::chrono::seconds(1));
182  }
183 
184  // All done, stop robot and put into IDLE mode
185  robot.Stop();
186 
187  } catch (const std::exception& e) {
188  spdlog::error(e.what());
189  return 1;
190  }
191 
192  return 0;
193 }
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:25
Data structure representing the customized data type "COORD" in Flexiv Elements.
Definition: data.hpp:334
Data structure representing the customized data type "JPOS" in Flexiv Elements.
Definition: data.hpp:300