Skip to content

Commit 10980a3

Browse files
committed
fix(fr3): pybind rcs module refs
1 parent b4ce691 commit 10980a3

File tree

3 files changed

+18
-12
lines changed

3 files changed

+18
-12
lines changed

extensions/rcs_fr3/src/pybind/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ set_target_properties(franka PROPERTIES
77
INTERPROCEDURAL_OPTIMIZATION TRUE
88
)
99
set_target_properties(_core PROPERTIES
10-
INSTALL_RPATH "$ORIGIN;$ORIGIN/../rcs_fr3"
10+
INSTALL_RPATH "$ORIGIN;$ORIGIN/../rcs"
1111
INTERPROCEDURAL_OPTIMIZATION TRUE
1212
)
1313
# in pip

extensions/rcs_fr3/src/pybind/rcs.cpp

Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ PYBIND11_MODULE(_core, m) {
4242
// HARDWARE MODULE
4343
auto hw = m.def_submodule("hw", "rcs fr3 module");
4444

45-
py::class_<rcs::hw::FR3State, rcs::common::RobotState>(hw, "FR3State")
45+
py::object robot_state = (py::object) py::module_::import("rcs").attr("common").attr("RobotState");
46+
py::class_<rcs::hw::FR3State>(hw, "FR3State", robot_state)
4647
.def(py::init<>());
4748
py::class_<rcs::hw::FR3Load>(hw, "FR3Load")
4849
.def(py::init<>())
@@ -55,7 +56,8 @@ PYBIND11_MODULE(_core, m) {
5556
.value("rcs_ik", rcs::hw::IKSolver::rcs_ik)
5657
.export_values();
5758

58-
py::class_<rcs::hw::FR3Config, rcs::common::RobotConfig>(hw, "FR3Config")
59+
py::object robot_config = (py::object) py::module_::import("rcs").attr("common").attr("RobotConfig");
60+
py::class_<rcs::hw::FR3Config>(hw, "FR3Config", robot_config)
5961
.def(py::init<>())
6062
.def_readwrite("ik_solver", &rcs::hw::FR3Config::ik_solver)
6163
.def_readwrite("speed_factor", &rcs::hw::FR3Config::speed_factor)
@@ -66,7 +68,8 @@ PYBIND11_MODULE(_core, m) {
6668
.def_readwrite("tcp_offset", &rcs::hw::FR3Config::tcp_offset)
6769
.def_readwrite("async_control", &rcs::hw::FR3Config::async_control);
6870

69-
py::class_<rcs::hw::FHConfig, rcs::common::GripperConfig>(hw, "FHConfig")
71+
py::object gripper_config = (py::object) py::module_::import("rcs").attr("common").attr("GripperConfig");
72+
py::class_<rcs::hw::FHConfig>(hw, "FHConfig", gripper_config)
7073
.def(py::init<>())
7174
.def_readwrite("grasping_width", &rcs::hw::FHConfig::grasping_width)
7275
.def_readwrite("speed", &rcs::hw::FHConfig::speed)
@@ -75,7 +78,8 @@ PYBIND11_MODULE(_core, m) {
7578
.def_readwrite("epsilon_outer", &rcs::hw::FHConfig::epsilon_outer)
7679
.def_readwrite("async_control", &rcs::hw::FHConfig::async_control);
7780

78-
py::class_<rcs::hw::FHState, rcs::common::GripperState>(hw, "FHState")
81+
py::object gripper_state = (py::object) py::module_::import("rcs").attr("common").attr("GripperState");
82+
py::class_<rcs::hw::FHState>(hw, "FHState", gripper_state)
7983
.def(py::init<>())
8084
.def_readonly("width", &rcs::hw::FHState::width)
8185
.def_readonly("is_grasped", &rcs::hw::FHState::is_grasped)
@@ -87,8 +91,9 @@ PYBIND11_MODULE(_core, m) {
8791
&rcs::hw::FHState::max_unnormalized_width)
8892
.def_readonly("temperature", &rcs::hw::FHState::temperature);
8993

90-
py::class_<rcs::hw::FR3, rcs::common::Robot, std::shared_ptr<rcs::hw::FR3>>(
91-
hw, "FR3")
94+
py::object robot = (py::object) py::module_::import("rcs").attr("common").attr("Robot");
95+
py::class_<rcs::hw::FR3, std::shared_ptr<rcs::hw::FR3>>(
96+
hw, "FR3", robot)
9297
.def(py::init<const std::string &,
9398
std::optional<std::shared_ptr<rcs::common::IK>>>(),
9499
py::arg("ip"), py::arg("ik") = std::nullopt)
@@ -117,8 +122,9 @@ PYBIND11_MODULE(_core, m) {
117122
&rcs::hw::FR3::set_cartesian_position_internal, py::arg("pose"),
118123
py::arg("max_time"), py::arg("elbow"), py::arg("max_force") = 5);
119124

120-
py::class_<rcs::hw::FrankaHand, rcs::common::Gripper,
121-
std::shared_ptr<rcs::hw::FrankaHand>>(hw, "FrankaHand")
125+
py::object gripper = (py::object) py::module_::import("rcs").attr("common").attr("Gripper");
126+
py::class_<rcs::hw::FrankaHand,
127+
std::shared_ptr<rcs::hw::FrankaHand>>(hw, "FrankaHand", gripper)
122128
.def(py::init<const std::string &, const rcs::hw::FHConfig &>(),
123129
py::arg("ip"), py::arg("cfg"))
124130
.def("get_parameters", &rcs::hw::FrankaHand::get_parameters)

extensions/rcs_fr3/src/rcs_fr3/creators.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -47,12 +47,12 @@ def __call__( # type: ignore
4747
Args:
4848
ip (str): IP address of the robot.
4949
control_mode (ControlMode): Control mode for the robot.
50-
robot_cfg (rcs.hw.FR3Config): Configuration for the FR3 robot.
50+
robot_cfg (hw.FR3Config): Configuration for the FR3 robot.
5151
collision_guard (str | PathLike | None): Key to a built-in scene
52-
robot_cfg (rcs.hw.FR3Config): Configuration for the FR3 robot.
52+
robot_cfg (hw.FR3Config): Configuration for the FR3 robot.
5353
collision_guard (str | PathLike | None): Key to a scene (requires UTN compatible scene package to be present)
5454
or the path to a mujoco scene for collision guarding. If None, collision guarding is not used.
55-
gripper_cfg (rcs.hw.FHConfig | None): Configuration for the gripper. If None, no gripper is used.
55+
gripper_cfg (hw.FHConfig | None): Configuration for the gripper. If None, no gripper is used.
5656
camera_set (BaseHardwareCameraSet | None): Camera set to be used. If None, no cameras are used.
5757
max_relative_movement (float | tuple[float, float] | None): Maximum allowed movement. If float, it restricts
5858
translational movement in meters. If tuple, it restricts both translational (in meters) and rotational

0 commit comments

Comments
 (0)