Flexiv RDK APIs  1.4
intermediate2_realtime_joint_impedance_control.cpp
1 
8 #include <flexiv/rdk/robot.hpp>
10 #include <flexiv/rdk/utility.hpp>
11 #include <spdlog/spdlog.h>
12 
13 #include <iostream>
14 #include <string>
15 #include <cmath>
16 #include <thread>
17 #include <atomic>
18 
19 namespace {
21 constexpr double kLoopPeriod = 0.001;
22 
24 constexpr double kSineAmp = 0.035;
25 constexpr double kSineFreq = 0.3;
26 
28 std::atomic<bool> g_stop_sched = {false};
29 }
30 
32 void PrintHelp()
33 {
34  // clang-format off
35  std::cout << "Required arguments: [robot SN]" << std::endl;
36  std::cout << " robot SN: Serial number of the robot to connect to. "
37  "Remove any space, for example: Rizon4s-123456" << std::endl;
38  std::cout << "Optional arguments: [--hold]" << std::endl;
39  std::cout << " --hold: robot holds current joint positions, otherwise do a sine-sweep" << std::endl;
40  std::cout << std::endl;
41  // clang-format on
42 }
43 
45 void PeriodicTask(
46  flexiv::rdk::Robot& robot, const std::string& motion_type, const std::vector<double>& init_pos)
47 {
48  // Local periodic loop counter
49  static unsigned int loop_counter = 0;
50 
51  try {
52  // Monitor fault on the connected robot
53  if (robot.fault()) {
54  throw std::runtime_error(
55  "PeriodicTask: Fault occurred on the connected robot, exiting ...");
56  }
57 
58  // Initialize target vectors to hold position
59  std::vector<double> target_pos(robot.info().DoF);
60  std::vector<double> target_vel(robot.info().DoF);
61  std::vector<double> target_acc(robot.info().DoF);
62 
63  // Set target vectors based on motion type
64  if (motion_type == "hold") {
65  target_pos = init_pos;
66  } else if (motion_type == "sine-sweep") {
67  for (size_t i = 0; i < target_pos.size(); ++i) {
68  target_pos[i] = init_pos[i]
69  + kSineAmp * sin(2 * M_PI * kSineFreq * loop_counter * kLoopPeriod);
70  }
71  } else {
72  throw std::invalid_argument(
73  "PeriodicTask: unknown motion type. Accepted motion types: hold, sine-sweep");
74  }
75 
76  // Reduce joint stiffness to half of nominal values after 5 seconds
77  if (loop_counter == 5000) {
78  auto new_Kq = robot.info().K_q_nom;
79  for (auto& v : new_Kq) {
80  v *= 0.5;
81  }
82  robot.SetJointImpedance(new_Kq);
83  spdlog::info(
84  "PeriodicTask: joint stiffness set to [{}]", flexiv::rdk::utility::Vec2Str(new_Kq));
85  }
86 
87  // Reset joint stiffness to nominal values after another 5 seconds
88  if (loop_counter == 10000) {
89  robot.ResetJointImpedance();
90  spdlog::info("PeriodicTask: joint stiffness reset to [{}]",
91  flexiv::rdk::utility::Vec2Str(robot.info().K_q_nom));
92  }
93 
94  // Send commands
95  robot.StreamJointPosition(target_pos, target_vel, target_acc);
96 
97  // Increment loop counter
98  loop_counter++;
99 
100  } catch (const std::exception& e) {
101  spdlog::error(e.what());
102  g_stop_sched = true;
103  }
104 }
105 
106 int main(int argc, char* argv[])
107 {
108  // Program Setup
109  // =============================================================================================
110  // Parse parameters
111  if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
112  PrintHelp();
113  return 1;
114  }
115  // Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456
116  std::string robot_sn = argv[1];
117 
118  // Print description
119  spdlog::info(
120  ">>> Tutorial description <<<\nThis tutorial runs real-time joint impedance control to "
121  "hold or sine-sweep all robot joints.");
122 
123  // Type of motion specified by user
124  std::string motion_type = "";
125  if (flexiv::rdk::utility::ProgramArgsExist(argc, argv, "--hold")) {
126  spdlog::info("Robot holding current pose");
127  motion_type = "hold";
128  } else {
129  spdlog::info("Robot running joint sine-sweep");
130  motion_type = "sine-sweep";
131  }
132 
133  try {
134  // RDK Initialization
135  // =========================================================================================
136  // Instantiate robot interface
137  flexiv::rdk::Robot robot(robot_sn);
138 
139  // Clear fault on the connected robot if any
140  if (robot.fault()) {
141  spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
142  // Try to clear the fault
143  if (!robot.ClearFault()) {
144  spdlog::error("Fault cannot be cleared, exiting ...");
145  return 1;
146  }
147  spdlog::info("Fault on the connected robot is cleared");
148  }
149 
150  // Enable the robot, make sure the E-stop is released before enabling
151  spdlog::info("Enabling robot ...");
152  robot.Enable();
153 
154  // Wait for the robot to become operational
155  while (!robot.operational()) {
156  std::this_thread::sleep_for(std::chrono::seconds(1));
157  }
158  spdlog::info("Robot is now operational");
159 
160  // Move robot to home pose
161  spdlog::info("Moving to home pose");
162  robot.SwitchMode(flexiv::rdk::Mode::NRT_PRIMITIVE_EXECUTION);
163  robot.ExecutePrimitive("Home()");
164 
165  // Wait for the primitive to finish
166  while (robot.busy()) {
167  std::this_thread::sleep_for(std::chrono::seconds(1));
168  }
169 
170  // Real-time Joint Impedance Control
171  // =========================================================================================
172  // Switch to real-time joint impedance control mode
173  robot.SwitchMode(flexiv::rdk::Mode::RT_JOINT_IMPEDANCE);
174 
175  // Set initial joint positions
176  auto init_pos = robot.states().q;
177  spdlog::info("Initial joint positions set to: {}", flexiv::rdk::utility::Vec2Str(init_pos));
178 
179  // Create real-time scheduler to run periodic tasks
180  flexiv::rdk::Scheduler scheduler;
181  // Add periodic task with 1ms interval and highest applicable priority
182  scheduler.AddTask(
183  std::bind(PeriodicTask, std::ref(robot), std::ref(motion_type), std::ref(init_pos)),
184  "HP periodic", 1, scheduler.max_priority());
185  // Start all added tasks
186  scheduler.Start();
187 
188  // Block and wait for signal to stop scheduler tasks
189  while (!g_stop_sched) {
190  std::this_thread::sleep_for(std::chrono::milliseconds(1));
191  }
192  // Received signal to stop scheduler tasks
193  scheduler.Stop();
194 
195  } catch (const std::exception& e) {
196  spdlog::error(e.what());
197  return 1;
198  }
199 
200  return 0;
201 }
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:24
const RobotStates states() const
[Non-blocking] Access the current robot states.
void SetJointImpedance(const std::vector< double > &K_q, const std::vector< double > &Z_q={0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7})
[Non-blocking] Set impedance properties of the robot's joint motion controller used in the joint impe...
const RobotInfo info() const
[Non-blocking] Access general information of the robot.
bool operational(bool verbose=true) const
[Non-blocking] Whether the robot is normally operational, which requires the following conditions to ...
void ExecutePrimitive(const std::string &pt_cmd)
[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexi...
void SwitchMode(Mode mode)
[Blocking] Switch to a new control mode and wait until mode transition is finished.
void ResetJointImpedance()
[Non-blocking] Reset impedance properties of the robot's joint motion controller to nominal values.
void StreamJointPosition(const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations)
[Non-blocking] Continuously stream joint position, velocity, and acceleration command to the robot....
void Enable()
[Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brake...
bool fault() const
[Non-blocking] Whether the robot is in fault state.
bool ClearFault(unsigned int timeout_sec=30)
[Blocking] Try to clear minor or critical fault of the robot without a power cycle.
bool busy() const
[Non-blocking] Whether the robot is currently executing a task. This includes any user commanded oper...
Real-time scheduler that can simultaneously run multiple periodic tasks. Parameters for each task are...
Definition: scheduler.hpp:22
int max_priority() const
[Non-blocking] Get maximum available priority for user tasks.
void AddTask(std::function< void(void)> &&callback, const std::string &task_name, int interval, int priority, int cpu_affinity=-1)
[Non-blocking] Add a new periodic task to the scheduler's task pool. Each task in the pool is assigne...
void Stop()
[Blocking] Stop all added tasks. The periodic execution will stop and all task threads will be closed...
void Start()
[Blocking] Start all added tasks. A dedicated thread will be created for each added task and the peri...
std::vector< double > K_q_nom
Definition: data.hpp:57
std::vector< double > q
Definition: data.hpp:95