Skip to content

Commit f5462cd

Browse files
committed
style(fr3): cpp format and stub files
1 parent a09ad85 commit f5462cd

File tree

2 files changed

+27
-14
lines changed

2 files changed

+27
-14
lines changed

extensions/rcs_fr3/_core/hw/__init__.pyi

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,9 @@ class FR3(rcs._core.common.Robot):
6060
def double_tap_robot_to_continue(self) -> None: ...
6161
def get_parameters(self) -> FR3Config: ...
6262
def get_state(self) -> FR3State: ...
63-
def osc_set_cartesian_position(self, desired_pos_EE_in_base_frame: rcs._core.common.Pose) -> None: ...
63+
def osc_set_cartesian_position(
64+
self, desired_pos_EE_in_base_frame: rcs._core.common.Pose
65+
) -> None: ...
6466
def set_cartesian_position_ik(
6567
self,
6668
pose: rcs._core.common.Pose,
@@ -96,7 +98,12 @@ class FR3Config(rcs._core.common.RobotConfig):
9698

9799
class FR3Load:
98100
f_x_cload: numpy.ndarray[typing.Literal[3], numpy.dtype[numpy.float64]] | None
99-
load_inertia: numpy.ndarray[tuple[typing.Literal[3], typing.Literal[3]], numpy.dtype[numpy.float64]] | None
101+
load_inertia: (
102+
numpy.ndarray[
103+
tuple[typing.Literal[3], typing.Literal[3]], numpy.dtype[numpy.float64]
104+
]
105+
| None
106+
)
100107
load_mass: float
101108
def __init__(self) -> None: ...
102109

extensions/rcs_fr3/src/pybind/rcs.cpp

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

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)
47-
.def(py::init<>());
45+
py::object robot_state =
46+
(py::object)py::module_::import("rcs").attr("common").attr("RobotState");
47+
py::class_<rcs::hw::FR3State>(hw, "FR3State", robot_state).def(py::init<>());
4848
py::class_<rcs::hw::FR3Load>(hw, "FR3Load")
4949
.def(py::init<>())
5050
.def_readwrite("load_mass", &rcs::hw::FR3Load::load_mass)
@@ -56,7 +56,8 @@ PYBIND11_MODULE(_core, m) {
5656
.value("rcs_ik", rcs::hw::IKSolver::rcs_ik)
5757
.export_values();
5858

59-
py::object robot_config = (py::object) py::module_::import("rcs").attr("common").attr("RobotConfig");
59+
py::object robot_config =
60+
(py::object)py::module_::import("rcs").attr("common").attr("RobotConfig");
6061
py::class_<rcs::hw::FR3Config>(hw, "FR3Config", robot_config)
6162
.def(py::init<>())
6263
.def_readwrite("ik_solver", &rcs::hw::FR3Config::ik_solver)
@@ -68,7 +69,9 @@ PYBIND11_MODULE(_core, m) {
6869
.def_readwrite("tcp_offset", &rcs::hw::FR3Config::tcp_offset)
6970
.def_readwrite("async_control", &rcs::hw::FR3Config::async_control);
7071

71-
py::object gripper_config = (py::object) py::module_::import("rcs").attr("common").attr("GripperConfig");
72+
py::object gripper_config =
73+
(py::object)py::module_::import("rcs").attr("common").attr(
74+
"GripperConfig");
7275
py::class_<rcs::hw::FHConfig>(hw, "FHConfig", gripper_config)
7376
.def(py::init<>())
7477
.def_readwrite("grasping_width", &rcs::hw::FHConfig::grasping_width)
@@ -78,7 +81,9 @@ PYBIND11_MODULE(_core, m) {
7881
.def_readwrite("epsilon_outer", &rcs::hw::FHConfig::epsilon_outer)
7982
.def_readwrite("async_control", &rcs::hw::FHConfig::async_control);
8083

81-
py::object gripper_state = (py::object) py::module_::import("rcs").attr("common").attr("GripperState");
84+
py::object gripper_state =
85+
(py::object)py::module_::import("rcs").attr("common").attr(
86+
"GripperState");
8287
py::class_<rcs::hw::FHState>(hw, "FHState", gripper_state)
8388
.def(py::init<>())
8489
.def_readonly("width", &rcs::hw::FHState::width)
@@ -91,9 +96,9 @@ PYBIND11_MODULE(_core, m) {
9196
&rcs::hw::FHState::max_unnormalized_width)
9297
.def_readonly("temperature", &rcs::hw::FHState::temperature);
9398

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)
99+
py::object robot =
100+
(py::object)py::module_::import("rcs").attr("common").attr("Robot");
101+
py::class_<rcs::hw::FR3, std::shared_ptr<rcs::hw::FR3>>(hw, "FR3", robot)
97102
.def(py::init<const std::string &,
98103
std::optional<std::shared_ptr<rcs::common::IK>>>(),
99104
py::arg("ip"), py::arg("ik") = std::nullopt)
@@ -122,9 +127,10 @@ PYBIND11_MODULE(_core, m) {
122127
&rcs::hw::FR3::set_cartesian_position_internal, py::arg("pose"),
123128
py::arg("max_time"), py::arg("elbow"), py::arg("max_force") = 5);
124129

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)
130+
py::object gripper =
131+
(py::object)py::module_::import("rcs").attr("common").attr("Gripper");
132+
py::class_<rcs::hw::FrankaHand, std::shared_ptr<rcs::hw::FrankaHand>>(
133+
hw, "FrankaHand", gripper)
128134
.def(py::init<const std::string &, const rcs::hw::FHConfig &>(),
129135
py::arg("ip"), py::arg("cfg"))
130136
.def("get_parameters", &rcs::hw::FrankaHand::get_parameters)

0 commit comments

Comments
 (0)