Skip to content

Commit

Permalink
Flexiv RDK 0.4.0 (#6)
Browse files Browse the repository at this point in the history
  • Loading branch information
pzhu-flexiv authored Jan 17, 2022
1 parent a83755a commit 1865733
Show file tree
Hide file tree
Showing 33 changed files with 1,201 additions and 515 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/cmake.yml
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ jobs:
# Build examples and tests
run: |
cd ${{github.workspace}}/build
make -j4
make -j$(nproc)
build-ubuntu18:
# The CMake configure and build commands are platform agnostic and should work equally
Expand All @@ -60,6 +60,6 @@ jobs:
# Build examples and tests
run: |
cd ${{github.workspace}}/build
make -j4
make -j$(nproc)
33 changes: 25 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,21 +3,25 @@
![CMake Badge](https://github.com/flexivrobotics/flexiv_rdk/actions/workflows/cmake.yml/badge.svg)
[![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0)

Flexiv Robot Development Kit (RDK) is a C++ library for creating powerful real-time applications with Flexiv robots.
Flexiv RDK (Robot Development Kit) is a powerful toolkit as an add-on to the Flexiv software platform. It enables the users to create complex applications with APIs that provide low-level real-time access to the robot.

**C++** interface (real-time and non-real-time APIs) and **Python** interface (non-real-time APIs only) are supported.

## License

Flexiv RDK is licensed under the [Apache 2.0 license](https://www.apache.org/licenses/LICENSE-2.0.html).

## References

Please refer to **[Flexiv RDK Manual](https://flexivrobotics.github.io/)** on how to properly set up the system and use Flexiv RDK library.
**[Flexiv RDK Manual](https://flexivrobotics.github.io/)** is the main reference and contains important information on how to properly set up the system and use Flexiv RDK library.

[API documentation](https://flexivrobotics.github.io/flexiv_rdk/) contains details about available APIs, generated from Doxygen.

For details about the APIs, please refer to the [Doxygen generated API documentation](https://flexivrobotics.github.io/flexiv_rdk/).
## Run example programs

## Build and run the examples
**NOTE:** the instruction below is only a quick reference, assuming you've already gone through the Flexiv RDK Manual.

**NOTE:** the following is only a quick reference, assuming you've already gone through Flexiv RDK Manual.
### C++ interface

1. Configure and build example programs:

Expand All @@ -27,14 +31,27 @@ For details about the APIs, please refer to the [Doxygen generated API documenta
make -j4

2. The compiled program binaries will be output to ``flexiv_rdk/build/example``
3. Assuming the robot is booted and connected, to run an example program:
3. Assume the robot is booted and connected, to run an example program:

cd flexiv_rdk/build/example
sudo ./<program_name> <robot_ip> <local_ip>
sudo ./<program_name> <robot_ip> <local_ip> <...>

### Python interface

**NOTE:** Python 3.8 is required to use this interface, see Flexiv RDK Manual for more details.

1. Make sure your Python version is 3.8.x:

python3 --version

2. Assume the robot is booted and connected, to run an example program:

cd flexiv_rdk/example_py
sudo python3 <program_name>.py <robot_ip> <local_ip> <...>

## Integrated visualization

Flexiv RDK has integrated visualization based on Meshcat. To use it, follow instructions below.
Flexiv RDK has integrated visualization (only available for C++ interface) based on Meshcat. To use this feature:

1. Install Meshcat server using ``pip``:

Expand Down
2 changes: 1 addition & 1 deletion doc/Doxyfile.in
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ PROJECT_NAME = "RDK"
# could be handy for archiving the generated documentation or if some version
# control system is used.

PROJECT_NUMBER = "0.3.0"
PROJECT_NUMBER = "0.4.0"

# Using the PROJECT_BRIEF tag one can provide an optional one line description
# for a project that appears at the top of each page and should give viewer a
Expand Down
78 changes: 21 additions & 57 deletions example/auto_recovery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
* otherwise run damped floating with joint soft limit disabled, so that the
* user can manually trigger a safety system recovery state by moving any joint
* close to its limit. See flexiv::Mode::MODE_AUTO_RECOVERY for more details.
* @copyright (C) 2016-2021 Flexiv Ltd. All Rights Reserved.
* @copyright Copyright (C) 2016-2021 Flexiv Ltd. All Rights Reserved.
* @author Flexiv
*/

Expand All @@ -14,43 +14,14 @@
#include <string>
#include <thread>

namespace {
// robot DOF
const int k_robotDofs = 7;

const std::vector<double> k_floatingDamping
= {10.0, 10.0, 5.0, 5.0, 1.0, 1.0, 1.0};

}

// callback function for realtime periodic task
void periodicTask(std::shared_ptr<flexiv::RobotStates> robotStates,
std::shared_ptr<flexiv::Robot> robot)
{
// read robot states
robot->getRobotStates(robotStates.get());

// set 0 joint torques
std::vector<double> torqueDesired(k_robotDofs, 0.0);

// add some velocity damping
for (size_t i = 0; i < k_robotDofs; ++i) {
torqueDesired[i] = -k_floatingDamping[i] * robotStates->m_dtheta[i];
}

// send target joint torque to RDK server, enable gravity compensation
// and joint-space APF
robot->streamJointTorque(torqueDesired, true, false);
}

int main(int argc, char* argv[])
{
// log object for printing message with timestamp and coloring
// Log object for printing message with timestamp and coloring
flexiv::Log log;

// Parse Parameters
//=============================================================================
// check if program has 3 arguments
// Check if program has 3 arguments
if (argc != 3) {
log.error("Invalid program arguments. Usage: <robot_ip> <local_ip>");
return 0;
Expand All @@ -63,55 +34,48 @@ int main(int argc, char* argv[])

// RDK Initialization
//=============================================================================
// instantiate robot interface
// Instantiate robot interface
auto robot = std::make_shared<flexiv::Robot>();

// create data struct for storing robot states
// Create data struct for storing robot states
auto robotStates = std::make_shared<flexiv::RobotStates>();

// initialize robot interface and connect to the robot server
// Initialize robot interface and connect to the robot server
robot->init(robotIP, localIP);

// wait for the connection to be established
// Wait for the connection to be established
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (!robot->isConnected());

// enable the robot, make sure the E-stop is released before enabling
// Enable the robot, make sure the E-stop is released before enabling
if (robot->enable()) {
log.info("Enabling robot ...");
}

// if the system is in recovery state, we can't use isOperational to tell if
// the enable process is done, so just wait for long enough
// Application-specific Code
//=============================================================================
// If the system is in recovery state, we can't use isOperational to tell if
// the enabling process is done, so just wait long enough for the process to
// finish
std::this_thread::sleep_for(std::chrono::seconds(8));

// Auto recover if needed
//=============================================================================
// start auto recovery if the system is in recovery state, the involved
// joints will start to move back into allowed position range
// Start auto recovery if the system is in recovery state, the involved
// Joints will start to move back into allowed position range
if (robot->isRecoveryState()) {
robot->startAutoRecovery();
// block forever, must reboot robot and restart user program after auto
// recovery is done
// Block forever, must reboot the robot and restart user program after
// auto recovery is done
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (true);
}
// otherwise the system is normal, run robot floating using joint torques
// Otherwise the system is normal, do nothing
else {
robot->setMode(flexiv::MODE_JOINT_TORQUE);
// wait for the mode to be switched
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (robot->getMode() != flexiv::MODE_JOINT_TORQUE);
log.info(
"Robot system is not in recovery state, nothing to be done, "
"exiting ...");
}

// High-priority Realtime Periodic Task @ 1kHz
//=============================================================================
// this is a blocking method, so all other user-defined background
// threads should be spawned before this
robot->start(std::bind(periodicTask, robotStates, robot));

return 0;
}
59 changes: 30 additions & 29 deletions example/cartesian_impedance_control.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/**
* @example cartesian_impedance_control.cpp
* Run Cartesian impedance control to hold or sine-sweep the robot TCP.
* @copyright (C) 2016-2021 Flexiv Ltd. All Rights Reserved.
* @copyright Copyright (C) 2016-2021 Flexiv Ltd. All Rights Reserved.
* @author Flexiv
*/

Expand All @@ -14,31 +14,32 @@

namespace {

// size of Cartesian pose vector [position 3x1 + rotation (quaternion) 4x1 ]
/** Size of Cartesian pose vector [position 3x1 + rotation (quaternion) 4x1 ] */
const unsigned int k_cartPoseSize = 7;

// RT loop period [sec]
/** RT loop period [sec] */
const double k_loopPeiord = 0.001;

// TCP sine-sweep amplitude [m]
/** TCP sine-sweep amplitude [m] */
const double k_swingAmp = 0.1;

// TCP sine-sweep frequency [Hz]
/** TCP sine-sweep frequency [Hz] */
const double k_swingFreq = 0.3;

// initial Cartesian-space pose (position + rotation) of robot TCP
/** Initial Cartesian-space pose (position + rotation) of robot TCP */
std::vector<double> g_initTcpPose;

// current Cartesian-space pose (position + rotation) of robot TCP
/** Current Cartesian-space pose (position + rotation) of robot TCP */
std::vector<double> g_currentTcpPose;

// flag whether initial Cartesian position is set
/** Flag whether initial Cartesian position is set */
bool g_isInitPoseSet = false;

// loop counter
/** Loop counter */
unsigned int g_loopCounter = 0;
}

/** Helper function to print a std::vector */
void printVector(const std::vector<double>& vec)
{
for (auto i : vec) {
Expand All @@ -47,20 +48,20 @@ void printVector(const std::vector<double>& vec)
std::cout << std::endl;
}

// callback function for realtime periodic task
/** Callback function for realtime periodic task */
void periodicTask(std::shared_ptr<flexiv::RobotStates> robotStates,
std::shared_ptr<flexiv::Robot> robot, std::string motionType)
{
// read robot states
// Read robot states
robot->getRobotStates(robotStates.get());

// use target TCP velocity and acceleration = 0
// Use target TCP velocity and acceleration = 0
std::vector<double> tcpVel(6, 0);
std::vector<double> tcpAcc(6, 0);

// set initial TCP pose
// Set initial TCP pose
if (!g_isInitPoseSet) {
// check vector size before saving
// Check vector size before saving
if (robotStates->m_tcpPose.size() == k_cartPoseSize) {
g_initTcpPose = robotStates->m_tcpPose;
g_currentTcpPose = g_initTcpPose;
Expand All @@ -70,9 +71,9 @@ void periodicTask(std::shared_ptr<flexiv::RobotStates> robotStates,
printVector(g_initTcpPose);
}
}
// run control only after initial pose is set
// Run control only after initial pose is set
else {
// set target position based on motion type
// Set target position based on motion type
if (motionType == "hold") {
robot->streamTcpPose(g_initTcpPose, tcpVel, tcpAcc);
} else if (motionType == "sine-sweep") {
Expand All @@ -93,12 +94,12 @@ void periodicTask(std::shared_ptr<flexiv::RobotStates> robotStates,

int main(int argc, char* argv[])
{
// log object for printing message with timestamp and coloring
// Log object for printing message with timestamp and coloring
flexiv::Log log;

// Parse Parameters
//=============================================================================
// check if program has 3 arguments
// Check if program has 3 arguments
if (argc != 4) {
log.error(
"Invalid program arguments. Usage: <robot_ip> <local_ip> "
Expand All @@ -112,51 +113,51 @@ int main(int argc, char* argv[])
// IP of the workstation PC running this program
std::string localIP = argv[2];

// type of motion specified by user
// Type of motion specified by user
std::string motionType = argv[3];

// RDK Initialization
//=============================================================================
// instantiate robot interface
// Instantiate robot interface
auto robot = std::make_shared<flexiv::Robot>();

// create data struct for storing robot states
// Create data struct for storing robot states
auto robotStates = std::make_shared<flexiv::RobotStates>();

// initialize robot interface and connect to the robot server
// Initialize robot interface and connect to the robot server
robot->init(robotIP, localIP);

// wait for the connection to be established
// Wait for the connection to be established
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (!robot->isConnected());

// enable the robot, make sure the E-stop is released before enabling
// Enable the robot, make sure the E-stop is released before enabling
if (robot->enable()) {
log.info("Enabling robot ...");
}

// wait for the robot to become operational
// Wait for the robot to become operational
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (!robot->isOperational());
log.info("Robot is now operational");

// set mode after robot is operational
// Set mode after robot is operational
robot->setMode(flexiv::MODE_CARTESIAN_IMPEDANCE);

// wait for the mode to be switched
// Wait for the mode to be switched
do {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
} while (robot->getMode() != flexiv::MODE_CARTESIAN_IMPEDANCE);

// choose the index of tool being used. No need to call this method if the
// Choose the index of tool being used. No need to call this method if the
// mounted tool on the robot has only one TCP, it'll be used by default
robot->switchTcp(0);

// High-priority Realtime Periodic Task @ 1kHz
//=============================================================================
// this is a blocking method, so all other user-defined background threads
// This is a blocking method, so all other user-defined background threads
// should be spawned before this
robot->start(std::bind(periodicTask, robotStates, robot, motionType));

Expand Down
Loading

0 comments on commit 1865733

Please sign in to comment.