Skip to content

Commit 168376f

Browse files
committed
style(fr3): cpp format and stub files
1 parent ce526fa commit 168376f

3 files changed

Lines changed: 21 additions & 21 deletions

File tree

Makefile

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,16 +35,14 @@ stubgen:
3535
find ./python/rcs/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[typing\.Literal\[\([0-9]\+\)\], typing\.Literal\[1\]\]/typing\.Literal[\1]/g'
3636
find ./python/rcs/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[\([M|N]\), typing\.Literal\[1\]\]/\1/g'
3737
ruff check --fix python/rcs/_core
38-
isort python/rcs/_core
39-
black python/rcs/_core
4038
pybind11-stubgen -o extensions --numpy-array-use-type-var rcs_fr3
4139
find ./extensions/rcs_fr3 -not -path "./extensions/rcs_fr3/_core/*" -name '*.pyi' -delete
4240
find ./extensions/rcs_fr3 -name '*.pyi' -print | xargs sed -i '1s/^/# ATTENTION: auto generated from C++ code, use `make stubgen` to update!\n/'
4341
find ./extensions/rcs_fr3/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[typing\.Literal\[\([0-9]\+\)\], typing\.Literal\[1\]\]/typing\.Literal[\1]/g'
4442
find ./extensions/rcs_fr3/_core -name '*.pyi' -print | xargs sed -i 's/tuple\[\([M|N]\), typing\.Literal\[1\]\]/\1/g'
4543
ruff check --fix extensions/rcs_fr3/_core
46-
isort extensions/rcs_fr3/_core
47-
black extensions/rcs_fr3/_core
44+
isort python/rcs/_core extensions/rcs_fr3/_core
45+
black python/rcs/_core extensions/rcs_fr3/_core
4846

4947
# Python
5048
pycheckformat:

extensions/rcs_fr3/_core/hw/__init__.pyi

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -62,11 +62,7 @@ class FR3(rcs._core.common.Robot):
6262
def get_state(self) -> FR3State: ...
6363
def osc_set_cartesian_position(self, desired_pos_EE_in_base_frame: rcs._core.common.Pose) -> None: ...
6464
def set_cartesian_position_ik(
65-
self,
66-
pose: rcs._core.common.Pose,
67-
max_time: float,
68-
elbow: float | None,
69-
max_force: float | None = 5,
65+
self, pose: rcs._core.common.Pose, max_time: float, elbow: float | None, max_force: float | None = 5
7066
) -> None: ...
7167
def set_cartesian_position_internal(self, pose: rcs._core.common.Pose) -> None: ...
7268
def set_default_robot_behavior(self) -> None: ...

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)