Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 1 addition & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,20 +39,14 @@ find_package(MuJoCo REQUIRED)
find_package(pinocchio REQUIRED)


FetchContent_Declare(rl
GIT_REPOSITORY https://github.com/roboticslibrary/rl.git
GIT_TAG 0b3797215345a1d37903634095361233d190b2e6
GIT_PROGRESS TRUE
EXCLUDE_FROM_ALL
)
FetchContent_Declare(pybind11
GIT_REPOSITORY https://github.com/pybind/pybind11.git
GIT_TAG v2.13.4
GIT_PROGRESS TRUE
EXCLUDE_FROM_ALL
)

FetchContent_MakeAvailable(rl pybind11)
FetchContent_MakeAvailable(pybind11)
include(compile_scenes)

add_subdirectory(src)
12 changes: 2 additions & 10 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,8 @@ stubgen:
find ./python/rcs/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[typing\.Literal\[\([0-9]\+\)\], typing\.Literal\[1\]\]/tuple\[typing\.Literal[\1]\]/g'
find ./python/rcs/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[\([M|N]\), typing\.Literal\[1\]\]/tuple\[\1\]/g'
ruff check --fix python/rcs/_core
pybind11-stubgen -o extensions --numpy-array-use-type-var rcs_fr3
find ./extensions/rcs_fr3 -not -path "./extensions/rcs_fr3/_core/*" -name '*.pyi' -delete
find ./extensions/rcs_fr3 -name '*.pyi' -print | xargs sed -i '1s/^/# ATTENTION: auto generated from C++ code, use `make stubgen` to update!\n/'
find ./extensions/rcs_fr3 -name '*.pyi' -print | xargs sed -i 's/tuple\[typing\.Literal\[\([0-9]\+\)\], typing\.Literal\[1\]\]/tuple\[typing\.Literal[\1]\]/g'
find ./extensions/rcs_fr3 -name '*.pyi' -print | xargs sed -i 's/tuple\[\([M|N]\), typing\.Literal\[1\]\]/tuple\[\1\]/g'
rm -r extensions/rcs_fr3/src/rcs_fr3/_core
mv extensions/rcs_fr3/_core/ extensions/rcs_fr3/src/rcs_fr3/
ruff check --fix extensions/rcs_fr3/src/rcs_fr3/_core
isort python/rcs/_core extensions/rcs_fr3/src/rcs_fr3/_core
black python/rcs/_core extensions/rcs_fr3/src/rcs_fr3/_core
isort python/rcs/_core
black python/rcs/_core

# Python
pycheckformat:
Expand Down
14 changes: 10 additions & 4 deletions examples/fr3/fr3_direct_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,11 @@ def main():
gripper: rcs.common.Gripper
if ROBOT_INSTANCE == RobotPlatform.SIMULATION:
simulation = sim.Sim(rcs.scenes["fr3_empty_world"].mjb)
urdf_path = rcs.scenes["fr3_empty_world"].urdf
ik = rcs.common.RL(str(urdf_path))
mjcf_path = rcs.scenes["fr3_empty_world"].mjcf_robot
ik = rcs.common.Pin(
mjcf_path,
"attachment_site_0",
)
cfg = sim.SimRobotConfig()
cfg.add_id("0")
cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
Expand Down Expand Up @@ -92,8 +95,11 @@ def main():
simulation.open_gui()

else:
urdf_path = rcs.scenes["fr3_empty_world"].urdf
ik = rcs.common.RL(str(urdf_path))
mjcf_path = rcs.scenes["fr3_empty_world"].mjcf_robot
ik = rcs.common.Pin(
mjcf_path,
"attachment_site_0",
)
robot = hw.FR3(ROBOT_IP, ik)
robot_cfg = hw.FR3Config()
robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
Expand Down
11 changes: 7 additions & 4 deletions extensions/rcs_fr3/src/hw/FR3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@

namespace rcs {
namespace hw {
FR3::FR3(const std::string &ip, std::optional<std::shared_ptr<common::IK>> ik,
FR3::FR3(const std::string &ip,
std::optional<std::shared_ptr<common::Kinematics>> ik,
const std::optional<FR3Config> &cfg)
: robot(ip), m_ik(ik) {
// set collision behavior and impedance
Expand Down Expand Up @@ -650,7 +651,9 @@ double quintic_polynomial_speed_profile(double time, double start_time,
// return (1 - std::cos(M_PI * progress)) / 2.0;
}

std::optional<std::shared_ptr<common::IK>> FR3::get_ik() { return this->m_ik; }
std::optional<std::shared_ptr<common::Kinematics>> FR3::get_ik() {
return this->m_ik;
}

void FR3::set_cartesian_position(const common::Pose &x) {
// pose is assumed to be in the robots coordinate frame
Expand Down Expand Up @@ -686,8 +689,8 @@ void FR3::set_cartesian_position_ik(const common::Pose &pose) {
"No inverse kinematics was provided. Cannot use IK to set cartesian "
"position.");
}
auto joints = this->m_ik.value()->ik(pose, this->get_joint_position(),
this->cfg.tcp_offset);
auto joints = this->m_ik.value()->inverse(pose, this->get_joint_position(),
this->cfg.tcp_offset);

if (joints.has_value()) {
this->set_joint_position(joints.value());
Expand Down
10 changes: 6 additions & 4 deletions extensions/rcs_fr3/src/hw/FR3.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include <string>
#include <thread>

#include "rcs/IK.h"
#include "rcs/Kinematics.h"
#include "rcs/LinearPoseTrajInterpolator.h"
#include "rcs/Pose.h"
#include "rcs/Robot.h"
Expand All @@ -34,6 +34,8 @@ struct FR3Config : common::RobotConfig {
// TODO: max force and elbow?
// TODO: we can either write specific bindings for each, or we use python
// dictionaries with these objects
common::RobotType robot_type = common::RobotType::FR3;
common::RobotPlatform robot_platform = common::RobotPlatform::HARDWARE;
IKSolver ik_solver = IKSolver::franka_ik;
double speed_factor = DEFAULT_SPEED_FACTOR;
std::optional<FR3Load> load_parameters = std::nullopt;
Expand All @@ -48,7 +50,7 @@ class FR3 : public common::Robot {
private:
franka::Robot robot;
FR3Config cfg;
std::optional<std::shared_ptr<common::IK>> m_ik;
std::optional<std::shared_ptr<common::Kinematics>> m_ik;
std::optional<std::thread> control_thread = std::nullopt;
common::LinearPoseTrajInterpolator traj_interpolator;
double controller_time = 0.0;
Expand All @@ -62,7 +64,7 @@ class FR3 : public common::Robot {

public:
FR3(const std::string &ip,
std::optional<std::shared_ptr<common::IK>> ik = std::nullopt,
std::optional<std::shared_ptr<common::Kinematics>> ik = std::nullopt,
const std::optional<FR3Config> &cfg = std::nullopt);
~FR3() override;

Expand Down Expand Up @@ -100,7 +102,7 @@ class FR3 : public common::Robot {

void set_cartesian_position(const common::Pose &pose) override;

std::optional<std::shared_ptr<common::IK>> get_ik() override;
std::optional<std::shared_ptr<common::Kinematics>> get_ik() override;

void set_cartesian_position_internal(const common::Pose &pose,
double max_time,
Expand Down
2 changes: 1 addition & 1 deletion extensions/rcs_fr3/src/hw/main.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <franka/exception.h>
#include <franka/gripper.h>
#include <franka/robot.h>
#include <rcs/IK.h>
#include <rcs/Kinematics.h>

#include <iostream>
#include <memory>
Expand Down
4 changes: 2 additions & 2 deletions extensions/rcs_fr3/src/pybind/rcs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

#include <memory>

#include "rcs/IK.h"
#include "rcs/Kinematics.h"
#include "rcs/Pose.h"
#include "rcs/Robot.h"
#include "rcs/utils.h"
Expand Down Expand Up @@ -99,7 +99,7 @@ PYBIND11_MODULE(_core, m) {
(py::object)py::module_::import("rcs").attr("common").attr("Robot");
py::class_<rcs::hw::FR3, std::shared_ptr<rcs::hw::FR3>>(hw, "FR3", robot)
.def(py::init<const std::string &,
std::optional<std::shared_ptr<rcs::common::IK>>>(),
std::optional<std::shared_ptr<rcs::common::Kinematics>>>(),
py::arg("ip"), py::arg("ik") = std::nullopt)
.def("set_config", &rcs::hw::FR3::set_config, py::arg("cfg"))
.def("get_config", &rcs::hw::FR3::get_config)
Expand Down
2 changes: 1 addition & 1 deletion extensions/rcs_fr3/src/rcs_fr3/_core/hw/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class FHState(rcs._core.common.GripperState):
def width(self) -> float: ...

class FR3(rcs._core.common.Robot):
def __init__(self, ip: str, ik: rcs._core.common.IK | None = None) -> None: ...
def __init__(self, ip: str, ik: rcs._core.common.Kinematics | None = None) -> None: ...
def automatic_error_recovery(self) -> None: ...
def controller_set_joint_position(
self, desired_q: numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]]
Expand Down
21 changes: 13 additions & 8 deletions extensions/rcs_fr3/src/rcs_fr3/creators.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ def __call__( # type: ignore
camera_set: HardwareCameraSet | None = None,
max_relative_movement: float | tuple[float, float] | None = None,
relative_to: RelativeTo = RelativeTo.LAST_STEP,
urdf_path: str | PathLike | None = None,
) -> gym.Env:
"""
Creates a hardware environment for the FR3 robot.
Expand All @@ -55,14 +54,16 @@ def __call__( # type: ignore
translational movement in meters. If tuple, it restricts both translational (in meters) and rotational
(in radians) movements. If None, no restriction is applied.
relative_to (RelativeTo): Specifies whether the movement is relative to a configured origin or the last step.
urdf_path (str | PathLike | None): Path to the URDF file. If None the included one is used. A URDF file is needed for collision guarding.

Returns:
gym.Env: The configured hardware environment for the FR3 robot.
"""
if urdf_path is None:
urdf_path = rcs.scenes["fr3_empty_world"].urdf
ik = rcs.common.RL(str(urdf_path)) if urdf_path is not None else None
ik = rcs.common.Pin(
robot_cfg.kinematic_model_path,
robot_cfg.attachment_site,
urdf=robot_cfg.kinematic_model_path.endswith(".urdf"),
)
# ik = rcs_robotics_library._core.rl.RoboticsLibraryIK(robot_cfg.kinematic_model_path)
robot = hw.FR3(ip, ik)
robot.set_config(robot_cfg)

Expand Down Expand Up @@ -111,11 +112,15 @@ def __call__( # type: ignore
camera_set: HardwareCameraSet | None = None,
max_relative_movement: float | tuple[float, float] | None = None,
relative_to: RelativeTo = RelativeTo.LAST_STEP,
urdf_path: str | PathLike | None = None,
) -> gym.Env:

urdf_path = rcs.scenes["fr3_empty_world"].urdf
ik = rcs.common.RL(str(urdf_path)) if urdf_path is not None else None
ik = rcs.common.Pin(
robot_cfg.kinematic_model_path,
robot_cfg.attachment_site,
urdf=robot_cfg.kinematic_model_path.endswith(".urdf"),
)
# ik = rcs_robotics_library._core.rl.RoboticsLibraryIK(robot_cfg.kinematic_model_path)

robots: dict[str, hw.FR3] = {}
for ip in ips:
robots[ip] = hw.FR3(ip, ik)
Expand Down
4 changes: 4 additions & 0 deletions extensions/rcs_fr3/src/rcs_fr3/utils.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,15 @@
from rcs_fr3._core import hw

import rcs
from rcs import common


def default_fr3_hw_robot_cfg(async_control: bool = False) -> hw.FR3Config:
robot_cfg = hw.FR3Config()
robot_cfg.robot_type = rcs.scenes["fr3_empty_world"].robot_type
robot_cfg.kinematic_model_path = rcs.scenes["fr3_empty_world"].mjcf_robot
robot_cfg.tcp_offset = common.Pose(common.FrankaHandTCPOffset())
robot_cfg.attachment_site = "attachment_site_0"
robot_cfg.speed_factor = 0.1
robot_cfg.ik_solver = hw.IKSolver.rcs_ik
robot_cfg.async_control = async_control
Expand Down
63 changes: 63 additions & 0 deletions extensions/rcs_robotics_library/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
cmake_minimum_required(VERSION 3.19)

project(
rcs_fr3
LANGUAGES C CXX
VERSION 0.4.0
DESCRIPTION "RCS robotics library integration"
)

set(CMAKE_MODULE_PATH "${PROJECT_SOURCE_DIR}/cmake" ${CMAKE_MODULE_PATH})

set(CMAKE_POLICY_DEFAULT_CMP0077 NEW) # Allow us to set options for subprojects

cmake_policy(SET CMP0048 NEW) # Set version in project
# Allow target properties affecting visibility during linking in static libraries
set(CMAKE_POLICY_DEFAULT_CMP0063 NEW)
cmake_policy(SET CMP0072 NEW) # Use GLVND instead of legacy libGL.so
cmake_policy(SET CMP0135 NEW) # Use timestamp of file extraction not download
cmake_policy(SET CMP0140 NEW) # Check return arguments

set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)

set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)

set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

set(BUILD_SHARED_LIBS OFF)
set(CMAKE_POSITION_INDEPENDENT_CODE ON)

set(RL_BUILD_DEMOS OFF)
set(RL_BUILD_RL_SG OFF)
set(RL_BUILD_TESTS OFF)
set(RL_BUILD_EXTRAS OFF)
set(BUILD_PYTHON_INTERFACE OFF)
set(BUILD_DOCUMENTATION OFF)

include(FetchContent)

find_package(Eigen3 REQUIRED)
find_package(Python3 COMPONENTS Interpreter Development REQUIRED)
find_package(pinocchio REQUIRED)
find_package(rcs REQUIRED)

FetchContent_Declare(rl
GIT_REPOSITORY https://github.com/roboticslibrary/rl.git
GIT_TAG 0b3797215345a1d37903634095361233d190b2e6
GIT_PROGRESS TRUE
EXCLUDE_FROM_ALL
)
FetchContent_Declare(pybind11
GIT_REPOSITORY https://github.com/pybind/pybind11.git
GIT_TAG v2.13.4
GIT_PROGRESS TRUE
EXCLUDE_FROM_ALL
)

FetchContent_MakeAvailable(rl pybind11)

add_subdirectory(src)
41 changes: 41 additions & 0 deletions extensions/rcs_robotics_library/Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
PYSRC = src
CPPSRC = src
COMPILE_MODE = Release

# CPP
cppcheckformat:
clang-format --dry-run -Werror -i $(shell find ${CPPSRC} -name '*.cpp' -o -name '*.cc' -o -name '*.h')

cppformat:
clang-format -Werror -i $(shell find ${CPPSRC} -name '*.cpp' -o -name '*.cc' -o -name '*.h')

cpplint:
clang-tidy -p=build --warnings-as-errors='*' $(shell find ${CPPSRC} -name '*.cpp' -o -name '*.cc' -name '*.h')

# import errors
# clang-tidy -p=build --warnings-as-errors='*' $(shell find extensions/rcs_fr3/src -name '*.cpp' -o -name '*.cc' -name '*.h')

gcccompile:
pip install --upgrade --requirement requirements_dev.txt
cmake -DCMAKE_BUILD_TYPE=${COMPILE_MODE} -DCMAKE_C_COMPILER=gcc -DCMAKE_CXX_COMPILER=g++ -B build -G Ninja
cmake --build build --target _core

clangcompile:
pip install --upgrade --requirement requirements_dev.txt
cmake -DCMAKE_BUILD_TYPE=${COMPILE_MODE} -DCMAKE_C_COMPILER=clang -DCMAKE_CXX_COMPILER=clang++ -B build -G Ninja
cmake --build build --target _core

# Auto generation of CPP binding stub files
stubgen:
pybind11-stubgen -o src --numpy-array-use-type-var rcs_robotics_library
find ./src -name '*.pyi' -print | xargs sed -i '1s/^/# ATTENTION: auto generated from C++ code, use `make stubgen` to update!\n/'
find ./src -not -path "./src/rcs_robotics_library/_core/*" -name '*.pyi' -delete
find ./src/rcs_robotics_library/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[typing\.Literal\[\([0-9]\+\)\], typing\.Literal\[1\]\]/tuple\[typing\.Literal[\1]\]/g'
find ./src/rcs_robotics_library/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[\([M|N]\), typing\.Literal\[1\]\]/tuple\[\1\]/g'
ruff check --fix src/rcs_robotics_library/_core
isort src/rcs_robotics_library/_core
black src/rcs_robotics_library/_core



.PHONY: cppcheckformat cppformat cpplint gcccompile clangcompile stubgen
10 changes: 10 additions & 0 deletions extensions/rcs_robotics_library/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# RCS Extension for the Robotics Library
Implements access to the C++ library "Robotics Library".

## Installation
```shell
pip install -ve .
```

## Usage

Loading