Skip to content

Commit

Permalink
Pre-release/v1.1 (#28)
Browse files Browse the repository at this point in the history
  • Loading branch information
pzhu-flexiv authored Aug 10, 2023
1 parent 3e5763e commit 8137e3d
Show file tree
Hide file tree
Showing 51 changed files with 545 additions and 650 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/cmake.yml
Original file line number Diff line number Diff line change
Expand Up @@ -125,12 +125,12 @@ jobs:
cd ${{github.workspace}}/example
mkdir build && cd build
cmake .. -DCMAKE_INSTALL_PREFIX=~/rdk_install
cmake --build . --config Release
cmake --build . --config Release -j $(nproc)
- name: Build tests
# Find and link to the flexiv_rdk INTERFACE library, then build all tests.
run: |
cd ${{github.workspace}}/test
mkdir build && cd build
cmake .. -DCMAKE_INSTALL_PREFIX=~/rdk_install
cmake --build . --config Release
cmake --build . --config Release -j $(nproc)
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
.DS_Store
config.h
build/
install/
cloned/
html/
__pycache__
23 changes: 7 additions & 16 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,9 @@
cmake_minimum_required(VERSION 3.4)
cmake_minimum_required(VERSION 3.18.6)

# ===================================================================
# PROJECT CONFIG
# PROJECT SETUP
# ===================================================================
project(flexiv_rdk VERSION 1.0.0)

# C++14 required
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
project(flexiv_rdk VERSION 1.1.0)

# Configure build type
if(NOT CMAKE_BUILD_TYPE)
Expand Down Expand Up @@ -69,7 +65,7 @@ if(fastrtps_FOUND)
endif()

# ===================================================================
# PROJECT LIBRARIES
# CREATE LIBRARY
# ===================================================================
# Create an INTERFACE library with no source file to compile
add_library(${PROJECT_NAME} INTERFACE)
Expand All @@ -91,16 +87,11 @@ target_link_libraries(${PROJECT_NAME} INTERFACE
fastcdr
)

# librt is required for Linux
if(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
target_link_libraries(${PROJECT_NAME} INTERFACE -lrt)
endif()

# Use moderate compiler warning option
if(MSVC)
target_compile_options(${PROJECT_NAME} INTERFACE /W1)
else()
if(CMAKE_HOST_UNIX)
target_compile_options(${PROJECT_NAME} INTERFACE -Wall -Wextra)
else()
target_compile_options(${PROJECT_NAME} INTERFACE /W1)
endif()

# Install the INTERFACE library
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 = "Flexiv RDK APIs"
# could be handy for archiving the generated documentation or if some version
# control system is used.

PROJECT_NUMBER = "1.0"
PROJECT_NUMBER = "1.1"

# 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
10 changes: 7 additions & 3 deletions example/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@

cmake_minimum_required(VERSION 3.4)
cmake_minimum_required(VERSION 3.18.6)
project(flexiv_rdk-examples)

set(CMAKE_CXX_STANDARD 14)
# Show verbose build info
SET(CMAKE_VERBOSE_MAKEFILE ON)

message("OS: ${CMAKE_SYSTEM_NAME}")
message("Processor: ${CMAKE_SYSTEM_PROCESSOR}")
Expand Down Expand Up @@ -44,4 +44,8 @@ find_package(flexiv_rdk REQUIRED)
foreach(example ${EXAMPLE_LIST})
add_executable(${example} ${example}.cpp)
target_link_libraries(${example} flexiv::flexiv_rdk)
# C++17 required
set_target_properties(${example} PROPERTIES
CXX_STANDARD 17
CXX_STANDARD_REQUIRED ON)
endforeach()
3 changes: 1 addition & 2 deletions example/basics1_display_robot_states.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -116,7 +115,7 @@ int main(int argc, char* argv[])
// Properly exit thread
lowPriorityThread.join();

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
3 changes: 1 addition & 2 deletions example/basics2_clear_fault.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -78,7 +77,7 @@ int main(int argc, char* argv[])
} else {
log.info("No fault on robot server");
}
} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
7 changes: 3 additions & 4 deletions example/basics3_primitive_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -157,14 +156,14 @@ int main(int argc, char* argv[])
log.info("Executing primitive: MoveL");

// Example to convert target quaternion [w,x,y,z] to Euler ZYX using utility functions
std::vector<double> targetQuat = {0.9185587, 0.1767767, 0.3061862, 0.1767767};
std::array<double, 4> targetQuat = {0.9185587, 0.1767767, 0.3061862, 0.1767767};
// ZYX = [30, 30, 30] degrees
auto targetEulerDeg = flexiv::utility::rad2Deg(flexiv::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::utility::vec2Str(targetEulerDeg) + "TRAJ START)");
"MoveL(target=0.0 0.0 0.0 " + flexiv::utility::arr2Str(targetEulerDeg) + "TRAJ START)");

// Wait for reached target
while (flexiv::utility::parsePtStates(robot.getPrimitiveStates(), "reachedTarget") != "1") {
Expand All @@ -174,7 +173,7 @@ int main(int argc, char* argv[])
// All done, stop robot and put into IDLE mode
robot.stop();

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
5 changes: 2 additions & 3 deletions example/basics4_plan_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -106,7 +105,7 @@ int main(int argc, char* argv[])
while (true) {
// Monitor fault on robot server
if (robot.isFault()) {
throw flexiv::ServerException("Fault occurred on robot server, exiting ...");
throw std::runtime_error("Fault occurred on robot server, exiting ...");
}

// Get user input
Expand Down Expand Up @@ -164,7 +163,7 @@ int main(int argc, char* argv[])
}
}

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
7 changes: 3 additions & 4 deletions example/basics5_zero_force_torque_sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -97,7 +96,7 @@ int main(int argc, char* argv[])
flexiv::RobotStates robotStates;
robot.getRobotStates(robotStates);
log.info("TCP force and moment reading in base frame BEFORE sensor zeroing: "
+ flexiv::utility::vec2Str(robotStates.extWrenchInBase) + "[N][Nm]");
+ flexiv::utility::arr2Str(robotStates.extWrenchInBase) + "[N][Nm]");

// Run the "ZeroFTSensor" primitive to automatically zero force and torque sensors
robot.setMode(flexiv::Mode::NRT_PRIMITIVE_EXECUTION);
Expand All @@ -116,9 +115,9 @@ int main(int argc, char* argv[])
// Get and print the current TCP force/moment readings
robot.getRobotStates(robotStates);
log.info("TCP force and moment reading in base frame AFTER sensor zeroing: "
+ flexiv::utility::vec2Str(robotStates.extWrenchInBase) + "[N][Nm]");
+ flexiv::utility::arr2Str(robotStates.extWrenchInBase) + "[N][Nm]");

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
3 changes: 1 addition & 2 deletions example/basics6_gripper_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Gripper.hpp>
#include <flexiv/Utility.hpp>
Expand Down Expand Up @@ -169,7 +168,7 @@ int main(int argc, char* argv[])
log.info("Program finished");
printThread.join();

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
9 changes: 4 additions & 5 deletions example/basics7_auto_recovery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Utility.hpp>

Expand Down Expand Up @@ -72,10 +71,10 @@ int main(int argc, char* argv[])
// process is done, so just wait long enough for the process to finish
std::this_thread::sleep_for(std::chrono::seconds(8));

// Start auto recovery if the system is in recovery state, the involved joints will start to
// move back into allowed position range
// Run automatic 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();
robot.runAutoRecovery();
// Block forever, must reboot the robot and restart user program after recovery is done
while (true) {
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand All @@ -85,7 +84,7 @@ int main(int argc, char* argv[])
else {
log.info("Robot system is not in recovery state, nothing to be done, exiting ...");
}
} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
29 changes: 12 additions & 17 deletions example/intermediate1_realtime_joint_position_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
*/

#include <flexiv/Robot.hpp>
#include <flexiv/Exception.hpp>
#include <flexiv/Log.hpp>
#include <flexiv/Scheduler.hpp>
#include <flexiv/Utility.hpp>
Expand Down Expand Up @@ -50,40 +49,36 @@ void printHelp()
/** @brief Callback function for realtime periodic task */
void periodicTask(flexiv::Robot& robot, flexiv::Scheduler& scheduler, flexiv::Log& log,
flexiv::RobotStates& robotStates, const std::string& motionType,
const std::vector<double>& initPos)
const std::array<double, flexiv::k_jointDOF>& initPos)
{
// Local periodic loop counter
static unsigned int loopCounter = 0;

try {
// Monitor fault on robot server
if (robot.isFault()) {
throw flexiv::ServerException(
"periodicTask: Fault occurred on robot server, exiting ...");
throw std::runtime_error("periodicTask: Fault occurred on robot server, exiting ...");
}

// Read robot states
robot.getRobotStates(robotStates);

// Robot degrees of freedom
size_t robotDOF = robotStates.q.size();
// Initialize target arrays to hold position
std::array<double, flexiv::k_jointDOF> targetPos = {};
std::array<double, flexiv::k_jointDOF> targetVel = {};
std::array<double, flexiv::k_jointDOF> targetAcc = {};

// Initialize target vectors to hold position
std::vector<double> targetPos(robotDOF, 0);
std::vector<double> targetVel(robotDOF, 0);
std::vector<double> targetAcc(robotDOF, 0);

// Set target vectors based on motion type
// Set target arrays based on motion type
if (motionType == "hold") {
targetPos = initPos;
} else if (motionType == "sine-sweep") {
for (size_t i = 0; i < robotDOF; ++i) {
for (size_t i = 0; i < flexiv::k_jointDOF; ++i) {
targetPos[i]
= initPos[i]
+ k_sineAmp * sin(2 * M_PI * k_sineFreq * loopCounter * k_loopPeriod);
}
} else {
throw flexiv::InputException(
throw std::invalid_argument(
"periodicTask: unknown motion type. Accepted motion types: hold, sine-sweep");
}

Expand All @@ -92,7 +87,7 @@ void periodicTask(flexiv::Robot& robot, flexiv::Scheduler& scheduler, flexiv::Lo

loopCounter++;

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
scheduler.stop();
}
Expand Down Expand Up @@ -184,7 +179,7 @@ int main(int argc, char* argv[])
// Set initial joint positions
robot.getRobotStates(robotStates);
auto initPos = robotStates.q;
log.info("Initial joint positions set to: " + flexiv::utility::vec2Str(initPos));
log.info("Initial joint positions set to: " + flexiv::utility::arr2Str(initPos));

// Create real-time scheduler to run periodic tasks
flexiv::Scheduler scheduler;
Expand All @@ -196,7 +191,7 @@ int main(int argc, char* argv[])
// Start all added tasks, this is by default a blocking method
scheduler.start();

} catch (const flexiv::Exception& e) {
} catch (const std::exception& e) {
log.error(e.what());
return 1;
}
Expand Down
Loading

0 comments on commit 8137e3d

Please sign in to comment.