Skip to content

Commit

Permalink
Release/v1.5 (#83)
Browse files Browse the repository at this point in the history
  • Loading branch information
pzhu-flexiv authored Nov 12, 2024
1 parent 7f020e6 commit 9ee458e
Show file tree
Hide file tree
Showing 71 changed files with 2,402 additions and 1,760 deletions.
3 changes: 3 additions & 0 deletions .github/ISSUE_TEMPLATE/feature_request.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@ assignees: pzhu-flexiv

---

**How urgent is this feature?**
On a scale of 1 to 10.

**Is your feature request related to a problem? Please describe.**
A clear and concise description of what the problem is. E.g. I'm always frustrated when [...]

Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ if(fastcdr_FOUND)
endif()

# Fast-DDS (Fast-RTPS)
find_package(fastrtps 2.6.2 REQUIRED)
find_package(fastrtps 2.6.7 REQUIRED)
if(fastrtps_FOUND)
message(STATUS "Found fastrtps: ${fastrtps_DIR}")
endif()
Expand Down
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Flexiv RDK (Robotic Development Kit), a key component of the Flexiv Robotic Soft

## References

[Flexiv RDK Home Page](https://rdk.flexiv.com/) is the main reference. It contains important information including user manual and API documentation.
[Flexiv RDK Home Page](https://www.flexiv.com/software/rdk) is the main reference. It contains important information including user manual and API documentation.

## Compatibility Overview

Expand All @@ -23,7 +23,7 @@ The **C++ and Python** RDK libraries are packed into a unified modern CMake proj

### Note

* The instructions below serve as a quick reference. You can find the full documentation at [Flexiv RDK Manual](https://rdk.flexiv.com/manual/).
* The instructions below serve as a quick reference. You can find the full documentation at [Flexiv RDK Manual](https://www.flexiv.com/software/rdk/manual).
* You might need to turn off your computer's firewall or whitelist the RDK programs to be able to establish connection with the robot.

### Install on Linux
Expand Down Expand Up @@ -112,7 +112,7 @@ For example:

## API Documentation

The complete and detailed API documentation of the **latest release** can be found at https://rdk.flexiv.com/api/. The API documentation of a previous release can be generated manually using Doxygen. For example, on Linux:
The complete and detailed API documentation of the **latest release** can be found at https://www.flexiv.com/software/rdk/api. The API documentation of a previous release can be generated manually using Doxygen. For example, on Linux:

sudo apt install doxygen-latex graphviz
cd flexiv_rdk
Expand Down
2 changes: 1 addition & 1 deletion cmake/FlexivInstallLibrary.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ macro(FlexivInstallLibrary)
include(CMakePackageConfigHelpers)
write_basic_package_version_file(
"${PROJECT_NAME}-config-version.cmake"
VERSION ${PACKAGE_VERSION}
VERSION ${PROJECT_VERSION}
COMPATIBILITY AnyNewerVersion
)

Expand Down
2 changes: 1 addition & 1 deletion cmake/flexiv_rdk-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ set(THREADS_PREFER_PTHREAD_FLAG ON)
find_dependency(Threads REQUIRED)
find_dependency(Eigen3 REQUIRED)
find_dependency(spdlog REQUIRED)
find_dependency(fastrtps 2.6.2 REQUIRED)
find_dependency(fastrtps 2.6.7 REQUIRED)
find_dependency(fastcdr 1.0.24 REQUIRED)

# Add targets file
Expand Down
3 changes: 2 additions & 1 deletion example/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,8 @@ set(EXAMPLE_LIST
basics6_gripper_control
basics7_auto_recovery
basics8_update_robot_tool
basics9_logging_behavior
basics9_global_variables
basics10_logging_behavior
intermediate7_robot_dynamics
)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* @example basics9_logging_behavior.cpp
* @example basics10_logging_behavior.cpp
* This tutorial shows how to change the logging behaviors of RDK client.
* @copyright Copyright (C) 2016-2024 Flexiv Ltd. All Rights Reserved.
* @author Flexiv
Expand All @@ -15,6 +15,8 @@
#include <iostream>
#include <string>

using namespace flexiv;

namespace {
constexpr char kDefaultLogPattern[] = "[%Y-%m-%d %H:%M:%S.%e] [%^%l%$] %v";
}
Expand All @@ -36,7 +38,7 @@ int main(int argc, char* argv[])
// Program Setup
// =============================================================================================
// Parse parameters
if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
PrintHelp();
return 1;
}
Expand All @@ -46,7 +48,7 @@ int main(int argc, char* argv[])
// Print description
spdlog::info(
">>> Tutorial description <<<\nThis tutorial shows how to change the logging behaviors of "
"RDK client.");
"RDK client.\n");

// Suppress log messages from RDK client
// =========================================================================================
Expand All @@ -57,7 +59,7 @@ int main(int argc, char* argv[])

// Instantiate RDK client, all info messages are suppressed
try {
flexiv::rdk::Robot robot(robot_sn);
rdk::Robot robot(robot_sn);
} catch (const std::exception& e) {
spdlog::error(e.what());
}
Expand All @@ -84,7 +86,7 @@ int main(int argc, char* argv[])

// Instantiate RDK client again, all messages are printed to console and output to a log file
try {
flexiv::rdk::Robot robot(robot_sn);
rdk::Robot robot(robot_sn);
} catch (const std::exception& e) {
spdlog::error(e.what());
}
Expand Down
18 changes: 12 additions & 6 deletions example/basics1_display_robot_states.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
#include <iostream>
#include <thread>

using namespace flexiv;

/** @brief Print program usage help */
void PrintHelp()
{
Expand All @@ -26,12 +28,16 @@ void PrintHelp()
}

/** @brief Print robot states data @ 1Hz */
void printRobotStates(flexiv::rdk::Robot& robot)
void PrintRobotStates(rdk::Robot& robot)
{
while (true) {
// Print all robot states in JSON format using the built-in ostream operator overloading
spdlog::info("Current robot states:");
std::cout << robot.states() << std::endl;

// Print digital inputs
spdlog::info("Current digital inputs:");
std::cout << rdk::utility::Arr2Str(robot.digital_inputs()) << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
}
}
Expand All @@ -41,7 +47,7 @@ int main(int argc, char* argv[])
// Program Setup
// =============================================================================================
// Parse parameters
if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
PrintHelp();
return 1;
}
Expand All @@ -51,13 +57,13 @@ int main(int argc, char* argv[])
// Print description
spdlog::info(
">>> Tutorial description <<<\nThis tutorial does the very first thing: check connection "
"with the robot server and print received robot states.");
"with the robot server and print received robot states.\n");

try {
// RDK Initialization
// =========================================================================================
// Instantiate robot interface
flexiv::rdk::Robot robot(robot_sn);
rdk::Robot robot(robot_sn);

// Clear fault on the connected robot if any
if (robot.fault()) {
Expand All @@ -83,8 +89,8 @@ int main(int argc, char* argv[])
// Print States
// =========================================================================================
// Use std::thread to do scheduling so that this example can run on all OS, since not all OS
// support flexiv::rdk::Scheduler
std::thread low_priority_thread(std::bind(printRobotStates, std::ref(robot)));
// support rdk::Scheduler
std::thread low_priority_thread(std::bind(PrintRobotStates, std::ref(robot)));

// Properly exit thread
low_priority_thread.join();
Expand Down
8 changes: 5 additions & 3 deletions example/basics2_clear_fault.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
#include <string>
#include <thread>

using namespace flexiv;

/** @brief Print program usage help */
void PrintHelp()
{
Expand All @@ -30,7 +32,7 @@ int main(int argc, char* argv[])
// Program Setup
// =============================================================================================
// Parse parameters
if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
PrintHelp();
return 1;
}
Expand All @@ -40,13 +42,13 @@ int main(int argc, char* argv[])
// Print description
spdlog::info(
">>> Tutorial description <<<\nThis tutorial clears minor or critical faults, if any, of "
"the connected robot.");
"the connected robot.\n");

try {
// RDK Initialization
// =========================================================================================
// Instantiate robot interface
flexiv::rdk::Robot robot(robot_sn);
rdk::Robot robot(robot_sn);

// Fault Clearing
// =========================================================================================
Expand Down
62 changes: 38 additions & 24 deletions example/basics3_primitive_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,11 @@
#include <spdlog/spdlog.h>

#include <iostream>
#include <iomanip>
#include <thread>

using namespace flexiv;

/** @brief Print program usage help */
void PrintHelp()
{
Expand All @@ -30,7 +33,7 @@ int main(int argc, char* argv[])
// Program Setup
// =============================================================================================
// Parse parameters
if (argc < 2 || flexiv::rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
if (argc < 2 || rdk::utility::ProgramArgsExistAny(argc, argv, {"-h", "--help"})) {
PrintHelp();
return 1;
}
Expand All @@ -41,13 +44,13 @@ int main(int argc, char* argv[])
spdlog::info(
">>> Tutorial description <<<\nThis tutorial executes several basic robot primitives (unit "
"skills). For detailed documentation on all available primitives, please see [Flexiv "
"Primitives](https://www.flexiv.com/primitives/).");
"Primitives](https://www.flexiv.com/primitives/).\n");

try {
// RDK Initialization
// =========================================================================================
// Instantiate robot interface
flexiv::rdk::Robot robot(robot_sn);
rdk::Robot robot(robot_sn);

// Clear fault on the connected robot if any
if (robot.fault()) {
Expand All @@ -73,7 +76,7 @@ int main(int argc, char* argv[])
// Execute Primitives
// =========================================================================================
// Switch to primitive execution mode
robot.SwitchMode(flexiv::rdk::Mode::NRT_PRIMITIVE_EXECUTION);
robot.SwitchMode(rdk::Mode::NRT_PRIMITIVE_EXECUTION);

// (1) Go to home pose
// -----------------------------------------------------------------------------------------
Expand All @@ -82,10 +85,10 @@ int main(int argc, char* argv[])
spdlog::info("Executing primitive: Home");

// Send command to robot
robot.ExecutePrimitive("Home()");
robot.ExecutePrimitive("Home", std::map<std::string, rdk::FlexivDataTypes> {});

// Wait for the primitive to finish
while (robot.busy()) {
// Wait for reached target
while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}

Expand All @@ -95,11 +98,17 @@ int main(int argc, char* argv[])
spdlog::info("Executing primitive: MoveJ");

// Send command to robot
robot.ExecutePrimitive("MoveJ(target=30 -45 0 90 0 40 30)");
robot.ExecutePrimitive(
"MoveJ", {{"target", std::vector<double> {30, -45, 0, 90, 0, 40, 30}}});

// Wait for reached target
while (
flexiv::rdk::utility::ParsePtStates(robot.primitive_states(), "reachedTarget") != "1") {
while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
// Print current primitive states
spdlog::info("Current primitive states:");
for (const auto& st : robot.primitive_states()) {
std::cout << st.first << ": " << rdk::utility::FlexivTypes2Str(st.second);
std::cout << std::endl;
}
std::this_thread::sleep_for(std::chrono::seconds(1));
}

Expand All @@ -118,16 +127,22 @@ int main(int argc, char* argv[])
spdlog::info("Executing primitive: MoveL");

// Send command to robot
robot.ExecutePrimitive(
"MoveL(target=0.65 -0.3 0.2 180 0 180 WORLD WORLD_ORIGIN,waypoints=0.45 0.1 0.2 180 0 "
"180 WORLD WORLD_ORIGIN : 0.45 -0.3 0.2 180 0 180 WORLD WORLD_ORIGIN, vel=0.2)");
robot.ExecutePrimitive("MoveL",
{
{"target", rdk::Coord({0.65, -0.3, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"})},
{"waypoints",
std::vector<rdk::Coord> {
rdk::Coord({0.45, 0.1, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"}),
rdk::Coord({0.45, -0.3, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"})}},
{"vel", 0.6},
{"zoneRadius", "Z50"},
});

// The [Move] series primitive won't terminate itself, so we determine if the robot has
// reached target location by checking the primitive state "reachedTarget = 1" in the list
// of current primitive states, and terminate the current primitive manually by sending a
// new primitive command.
while (
flexiv::rdk::utility::ParsePtStates(robot.primitive_states(), "reachedTarget") != "1") {
while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}

Expand All @@ -140,17 +155,16 @@ int main(int argc, char* argv[])
// Example to convert target quaternion [w,x,y,z] to Euler ZYX using utility functions
std::array<double, 4> targetQuat = {0.9185587, 0.1767767, 0.3061862, 0.1767767};
// ZYX = [30, 30, 30] degrees
auto targetEulerDeg
= flexiv::rdk::utility::Rad2Deg(flexiv::rdk::utility::Quat2EulerZYX(targetQuat));

// Send command to robot. This motion will hold current TCP position and only do TCP
// rotation
robot.ExecutePrimitive("MoveL(target=0.0 0.0 0.0 "
+ flexiv::rdk::utility::Arr2Str(targetEulerDeg) + "TRAJ START)");
auto targetEulerDeg = rdk::utility::Rad2Deg(rdk::utility::Quat2EulerZYX(targetQuat));

// Send command to robot. This motion will hold current TCP position and only do rotation
robot.ExecutePrimitive(
"MoveL", {
{"target", rdk::Coord({0.0, 0.0, 0.0}, targetEulerDeg, {"TRAJ", "START"})},
{"vel", 0.2},
});
// Wait for reached target
while (
flexiv::rdk::utility::ParsePtStates(robot.primitive_states(), "reachedTarget") != "1") {
while (!std::get<int>(robot.primitive_states()["reachedTarget"])) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}

Expand Down
Loading

0 comments on commit 9ee458e

Please sign in to comment.