Flexiv RDK APIs  1.6.0
intermediate7_robot_dynamics.cpp
1 
9 #include <flexiv/rdk/robot.hpp>
10 #include <flexiv/rdk/model.hpp>
11 #include <flexiv/rdk/utility.hpp>
12 #include <spdlog/spdlog.h>
13 
14 #include <iostream>
15 #include <iomanip>
16 #include <thread>
17 #include <chrono>
18 #include <mutex>
19 
20 using namespace flexiv;
21 
23 void PrintHelp()
24 {
25  // clang-format off
26  std::cout << "Required arguments: [robot_sn]" << std::endl;
27  std::cout << " robot_sn: Serial number of the robot to connect. Remove any space, e.g. Rizon4s-123456" << std::endl;
28  std::cout << "Optional arguments: None" << std::endl;
29  std::cout << std::endl;
30  // clang-format on
31 }
32 
33 int main(int argc, char* argv[])
34 {
35  // Program Setup
36  // =============================================================================================
37  // Parse parameters
38  if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
39  PrintHelp();
40  return 1;
41  }
42  // Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456
43  std::string robot_sn = argv[1];
44 
45  // Print description
46  spdlog::info(
47  ">>> Tutorial description <<<\nThis tutorial runs the integrated dynamics engine to obtain "
48  "robot Jacobian, mass matrix, and gravity torques. Also checks reachability of a Cartesian "
49  "pose.\n");
50 
51  try {
52  // RDK Initialization
53  // =========================================================================================
54  // Instantiate robot interface
55  rdk::Robot robot(robot_sn);
56 
57  // Clear fault on the connected robot if any
58  if (robot.fault()) {
59  spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
60  // Try to clear the fault
61  if (!robot.ClearFault()) {
62  spdlog::error("Fault cannot be cleared, exiting ...");
63  return 1;
64  }
65  spdlog::info("Fault on the connected robot is cleared");
66  }
67 
68  // Enable the robot, make sure the E-stop is released before enabling
69  spdlog::info("Enabling robot ...");
70  robot.Enable();
71 
72  // Wait for the robot to become operational
73  while (!robot.operational()) {
74  std::this_thread::sleep_for(std::chrono::seconds(1));
75  }
76  spdlog::info("Robot is now operational");
77 
78  // Move robot to home pose
79  spdlog::info("Moving to home pose");
80  robot.SwitchMode(rdk::Mode::NRT_PLAN_EXECUTION);
81  robot.ExecutePlan("PLAN-Home");
82  // Wait for the plan to finish
83  while (robot.busy()) {
84  std::this_thread::sleep_for(std::chrono::seconds(1));
85  }
86 
87  // Robot Dynamics
88  // =========================================================================================
89  // Initialize dynamics engine
90  rdk::Model model(robot);
91 
92  // Step dynamics engine 5 times
93  for (size_t i = 0; i < 5; i++) {
94  // Mark timer start point
95  auto tic = std::chrono::high_resolution_clock::now();
96 
97  // Update robot model in dynamics engine
98  model.Update(robot.states().q, robot.states().dtheta);
99 
100  // Compute gravity vector
101  auto g = model.g();
102 
103  // Compute mass matrix
104  auto M = model.M();
105 
106  // Compute Jacobian
107  auto J = model.J("flange");
108 
109  // Mark timer end point and get loop time
110  auto toc = std::chrono::high_resolution_clock::now();
111  auto computation_time
112  = std::chrono::duration_cast<std::chrono::microseconds>(toc - tic).count();
113 
114  // Print time used to compute g, M, J
115  spdlog::info("Computation time = {} us", computation_time);
116  // Print gravity
117  std::cout << "g = \n"
118  << std::fixed << std::setprecision(5) << g.transpose() << std::endl;
119  // Print mass matrix
120  std::cout << "M = \n" << std::fixed << std::setprecision(5) << M << std::endl;
121  // Print Jacobian
122  std::cout << "J = \n" << std::fixed << std::setprecision(5) << J << std::endl;
123  std::cout << std::endl;
124  }
125 
126  // Check reachability of a Cartesian pose based on current pose
127  auto pose_to_check = robot.states().tcp_pose;
128  pose_to_check[0] += 0.1;
129  spdlog::info(
130  "Checking reachability of Cartesian pose [{}]", rdk::utility::Arr2Str(pose_to_check));
131  auto result = model.reachable(pose_to_check, robot.states().q, true);
132  spdlog::info("Got a result: reachable = {}, IK solution = [{}]", result.first,
133  rdk::utility::Vec2Str(result.second));
134 
135  } catch (const std::exception& e) {
136  spdlog::error(e.what());
137  return 1;
138  }
139 
140  return 0;
141 }
Interface to access certain robot kinematics and dynamics data.
Definition: model.hpp:21
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:25