Flexiv RDK APIs  1.4
intermediate2_realtime_joint_impedance_control.cpp

This tutorial runs real-time joint impedance control to hold or sine-sweep all robot joints.

Author
Flexiv
#include <spdlog/spdlog.h>
#include <iostream>
#include <string>
#include <cmath>
#include <thread>
#include <atomic>
namespace {
constexpr double kLoopPeriod = 0.001;
constexpr double kSineAmp = 0.035;
constexpr double kSineFreq = 0.3;
std::atomic<bool> g_stop_sched = {false};
}
void PrintHelp()
{
// clang-format off
std::cout << "Required arguments: [robot SN]" << std::endl;
std::cout << " robot SN: Serial number of the robot to connect to. "
"Remove any space, for example: Rizon4s-123456" << std::endl;
std::cout << "Optional arguments: [--hold]" << std::endl;
std::cout << " --hold: robot holds current joint positions, otherwise do a sine-sweep" << std::endl;
std::cout << std::endl;
// clang-format on
}
void PeriodicTask(
flexiv::rdk::Robot& robot, const std::string& motion_type, const std::vector<double>& init_pos)
{
// Local periodic loop counter
static unsigned int loop_counter = 0;
try {
// Monitor fault on the connected robot
if (robot.fault()) {
throw std::runtime_error(
"PeriodicTask: Fault occurred on the connected robot, exiting ...");
}
// Initialize target vectors to hold position
std::vector<double> target_pos(robot.info().DoF);
std::vector<double> target_vel(robot.info().DoF);
std::vector<double> target_acc(robot.info().DoF);
// Set target vectors based on motion type
if (motion_type == "hold") {
target_pos = init_pos;
} else if (motion_type == "sine-sweep") {
for (size_t i = 0; i < target_pos.size(); ++i) {
target_pos[i] = init_pos[i]
+ kSineAmp * sin(2 * M_PI * kSineFreq * loop_counter * kLoopPeriod);
}
} else {
throw std::invalid_argument(
"PeriodicTask: unknown motion type. Accepted motion types: hold, sine-sweep");
}
// Reduce joint stiffness to half of nominal values after 5 seconds
if (loop_counter == 5000) {
auto new_Kq = robot.info().K_q_nom;
for (auto& v : new_Kq) {
v *= 0.5;
}
robot.SetJointImpedance(new_Kq);
spdlog::info(
"PeriodicTask: joint stiffness set to [{}]", flexiv::rdk::utility::Vec2Str(new_Kq));
}
// Reset joint stiffness to nominal values after another 5 seconds
if (loop_counter == 10000) {
spdlog::info("PeriodicTask: joint stiffness reset to [{}]",
flexiv::rdk::utility::Vec2Str(robot.info().K_q_nom));
}
// Send commands
robot.StreamJointPosition(target_pos, target_vel, target_acc);
// Increment loop counter
loop_counter++;
} catch (const std::exception& e) {
spdlog::error(e.what());
g_stop_sched = true;
}
}
int main(int argc, char* argv[])
{
// Program Setup
// =============================================================================================
// Parse parameters
if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
PrintHelp();
return 1;
}
// Serial number of the robot to connect to. Remove any space, for example: Rizon4s-123456
std::string robot_sn = argv[1];
// Print description
spdlog::info(
">>> Tutorial description <<<\nThis tutorial runs real-time joint impedance control to "
"hold or sine-sweep all robot joints.");
// Type of motion specified by user
std::string motion_type = "";
if (flexiv::rdk::utility::ProgramArgsExist(argc, argv, "--hold")) {
spdlog::info("Robot holding current pose");
motion_type = "hold";
} else {
spdlog::info("Robot running joint sine-sweep");
motion_type = "sine-sweep";
}
try {
// RDK Initialization
// =========================================================================================
// Instantiate robot interface
flexiv::rdk::Robot robot(robot_sn);
// Clear fault on the connected robot if any
if (robot.fault()) {
spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
// Try to clear the fault
if (!robot.ClearFault()) {
spdlog::error("Fault cannot be cleared, exiting ...");
return 1;
}
spdlog::info("Fault on the connected robot is cleared");
}
// Enable the robot, make sure the E-stop is released before enabling
spdlog::info("Enabling robot ...");
robot.Enable();
// Wait for the robot to become operational
while (!robot.operational()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
spdlog::info("Robot is now operational");
// Move robot to home pose
spdlog::info("Moving to home pose");
robot.SwitchMode(flexiv::rdk::Mode::NRT_PRIMITIVE_EXECUTION);
robot.ExecutePrimitive("Home()");
// Wait for the primitive to finish
while (robot.busy()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
// Real-time Joint Impedance Control
// =========================================================================================
// Switch to real-time joint impedance control mode
robot.SwitchMode(flexiv::rdk::Mode::RT_JOINT_IMPEDANCE);
// Set initial joint positions
auto init_pos = robot.states().q;
spdlog::info("Initial joint positions set to: {}", flexiv::rdk::utility::Vec2Str(init_pos));
// Create real-time scheduler to run periodic tasks
// Add periodic task with 1ms interval and highest applicable priority
scheduler.AddTask(
std::bind(PeriodicTask, std::ref(robot), std::ref(motion_type), std::ref(init_pos)),
"HP periodic", 1, scheduler.max_priority());
// Start all added tasks
scheduler.Start();
// Block and wait for signal to stop scheduler tasks
while (!g_stop_sched) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
// Received signal to stop scheduler tasks
scheduler.Stop();
} catch (const std::exception& e) {
spdlog::error(e.what());
return 1;
}
return 0;
}
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