This tutorial runs real-time Cartesian-space unified motion-force control. The Z axis of the chosen reference frame will be activated for explicit force control, while the rest axes in the same reference frame will stay motion controlled.
#include <spdlog/spdlog.h>
#include <iostream>
#include <cmath>
#include <thread>
#include <atomic>
using namespace flexiv;
namespace {
constexpr double kLoopPeriod = 0.001;
constexpr double kSwingAmp = 0.1;
constexpr double kSwingFreq = 0.3;
constexpr double kPressingForce = 5.0;
constexpr double kSearchVelocity = 0.02;
constexpr double kSearchDistance = 1.0;
const std::array<double, rdk::kCartDoF> kMaxWrenchForContactSearch
= {10.0, 10.0, 10.0, 3.0, 3.0, 3.0};
std::atomic<bool> g_stop_sched = {false};
}
void PrintHelp()
{
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: [--TCP] [--polish]" << std::endl;
std::cout << " --TCP: use TCP frame as reference frame for force control, otherwise use world frame" << std::endl;
std::cout << " --polish: run a simple polish motion along XY plane in world frame, otherwise hold robot motion in non-force-control axes"
<< std::endl
<< std::endl;
}
void PeriodicTask(rdk::Robot& robot, const std::array<double, rdk::kPoseSize>& init_pose,
rdk::CoordType force_ctrl_frame,
bool enable_polish)
{
static uint64_t loop_counter = 0;
try {
if (robot.fault()) {
throw std::runtime_error(
"PeriodicTask: Fault occurred on the connected robot, exiting ...");
}
auto target_pose = init_pose;
double Fz = 0.0;
if (force_ctrl_frame ==
rdk::CoordType::WORLD) {
Fz = kPressingForce;
}
else if (force_ctrl_frame ==
rdk::CoordType::TCP) {
Fz = -kPressingForce;
}
std::array<double, rdk::kCartDoF> target_wrench = {0.0, 0.0, Fz, 0.0, 0.0, 0.0};
if (enable_polish) {
target_pose[1] = init_pose[1]
+ kSwingAmp * sin(2 * M_PI * kSwingFreq * loop_counter * kLoopPeriod);
robot.StreamCartesianMotionForce(target_pose, target_wrench);
}
else {
robot.StreamCartesianMotionForce(init_pose, target_wrench);
}
loop_counter++;
} catch (const std::exception& e) {
spdlog::error(e.what());
g_stop_sched = true;
}
}
int main(int argc, char* argv[])
{
if (argc < 2 ||
rdk::utility::ProgramArgsExistAny(argc, argv, {
"-h",
"--help"})) {
PrintHelp();
return 1;
}
std::string robot_sn = argv[1];
spdlog::info(
">>> Tutorial description <<<\nThis tutorial runs real-time Cartesian-space unified "
"motion-force control. The Z axis of the chosen reference frame will be activated for "
"explicit force control, while the rest axes in the same reference frame will stay motion "
"controlled.\n");
auto force_ctrl_frame = rdk::CoordType::WORLD;
if (
rdk::utility::ProgramArgsExist(argc, argv,
"--TCP")) {
spdlog::info("Reference frame used for force control: robot TCP frame");
force_ctrl_frame = rdk::CoordType::TCP;
} else {
spdlog::info("Reference frame used for force control: robot world frame");
}
bool enable_polish = false;
if (rdk::utility::ProgramArgsExist(argc, argv, "--polish")) {
spdlog::info("Robot will run a polish motion along XY plane in robot world frame");
enable_polish = true;
} else {
spdlog::info("Robot will hold its motion in all non-force-controlled axes");
}
try {
rdk::Robot robot(robot_sn);
if (robot.fault()) {
spdlog::warn("Fault occurred on the connected robot, trying to clear ...");
if (!robot.ClearFault()) {
spdlog::error("Fault cannot be cleared, exiting ...");
return 1;
}
spdlog::info("Fault on the connected robot is cleared");
}
spdlog::info("Enabling robot ...");
robot.Enable();
while (!robot.operational()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
spdlog::info("Robot is now operational");
spdlog::info("Moving to home pose");
robot.SwitchMode(
rdk::Mode::NRT_PLAN_EXECUTION);
robot.ExecutePlan("PLAN-Home");
while (robot.busy()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
robot.SwitchMode(
rdk::Mode::NRT_PRIMITIVE_EXECUTION);
robot.ExecutePrimitive("ZeroFTSensor", std::map<std::string, rdk::FlexivDataTypes> {});
spdlog::warn(
"Zeroing force/torque sensors, make sure nothing is in contact with the robot");
while (robot.busy()) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
spdlog::info("Sensor zeroing complete");
spdlog::info("Searching for contact ...");
auto init_pose = robot.states().tcp_pose;
spdlog::info("Initial TCP pose set to [position 3x1, rotation (quaternion) 4x1]: "
+
rdk::utility::Arr2Str(init_pose));
robot.SwitchMode(
rdk::Mode::NRT_CARTESIAN_MOTION_FORCE);
robot.SetMaxContactWrench(kMaxWrenchForContactSearch);
auto target_pose = init_pose;
target_pose[2] -= kSearchDistance;
robot.SendCartesianMotionForce(target_pose, {}, kSearchVelocity);
bool is_contacted = false;
while (!is_contacted) {
Eigen::Vector3d ext_force = {robot.states().ext_wrench_in_world[0],
robot.states().ext_wrench_in_world[1], robot.states().ext_wrench_in_world[2]};
if (ext_force.norm() > kPressingForce) {
is_contacted = true;
spdlog::info("Contact detected at robot TCP");
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
robot.Stop();
robot.SetForceControlFrame(force_ctrl_frame);
robot.SetForceControlAxis(
std::array<bool, rdk::kCartDoF> {false, false, true, false, false, false});
robot.SwitchMode(
rdk::Mode::RT_CARTESIAN_MOTION_FORCE);
std::array<double, rdk::kCartDoF> inf;
inf.fill(std::numeric_limits<double>::infinity());
robot.SetMaxContactWrench(inf);
init_pose = robot.states().tcp_pose;
rdk::Scheduler scheduler;
scheduler.AddTask(std::bind(PeriodicTask, std::ref(robot), std::ref(init_pose),
std::ref(force_ctrl_frame), enable_polish),
"HP periodic", 1, scheduler.max_priority());
scheduler.Start();
while (!g_stop_sched) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
scheduler.Stop();
} catch (const std::exception& e) {
spdlog::error(e.what());
return 1;
}
return 0;
}