12 #include <spdlog/spdlog.h>
20 using namespace flexiv;
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;
33 int main(
int argc,
char* argv[])
38 if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {
"-h",
"--help"})) {
43 std::string robot_sn = argv[1];
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 "
59 spdlog::warn(
"Fault occurred on the connected robot, trying to clear ...");
61 if (!robot.ClearFault()) {
62 spdlog::error(
"Fault cannot be cleared, exiting ...");
65 spdlog::info(
"Fault on the connected robot is cleared");
69 spdlog::info(
"Enabling robot ...");
73 while (!robot.operational()) {
74 std::this_thread::sleep_for(std::chrono::seconds(1));
76 spdlog::info(
"Robot is now operational");
79 spdlog::info(
"Moving to home pose");
80 robot.SwitchMode(rdk::Mode::NRT_PLAN_EXECUTION);
81 robot.ExecutePlan(
"PLAN-Home");
83 while (robot.busy()) {
84 std::this_thread::sleep_for(std::chrono::seconds(1));
93 for (
size_t i = 0; i < 5; i++) {
95 auto tic = std::chrono::high_resolution_clock::now();
98 model.Update(robot.states().q, robot.states().dtheta);
107 auto J = model.J(
"flange");
110 auto toc = std::chrono::high_resolution_clock::now();
111 auto computation_time
112 = std::chrono::duration_cast<std::chrono::microseconds>(toc - tic).count();
115 spdlog::info(
"Computation time = {} us", computation_time);
117 std::cout <<
"g = \n"
118 << std::fixed << std::setprecision(5) << g.transpose() << std::endl;
120 std::cout <<
"M = \n" << std::fixed << std::setprecision(5) << M << std::endl;
122 std::cout <<
"J = \n" << std::fixed << std::setprecision(5) << J << std::endl;
123 std::cout << std::endl;
127 auto pose_to_check = robot.states().tcp_pose;
128 pose_to_check[0] += 0.1;
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));
135 }
catch (
const std::exception& e) {
136 spdlog::error(e.what());
Interface to access certain robot kinematics and dynamics data.
Main interface with the robot, containing several function categories and background services.