Skip to content

Commit fa0aa5c

Browse files
committed
refactor: stubs and ik solver rename to fit rcs package
1 parent 00b8ac9 commit fa0aa5c

7 files changed

Lines changed: 18 additions & 18 deletions

File tree

python/examples/fr3.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ def main():
9494
robot = rcs.hw.FR3(ROBOT_IP, ik)
9595
robot_cfg = FR3Config()
9696
robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
97-
robot_cfg.ik_solver = IKSolver.rcs
97+
robot_cfg.ik_solver = IKSolver.rcs_ik
9898
robot.set_parameters(robot_cfg)
9999

100100
gripper_cfg_hw = rcs.hw.FHConfig()

python/rcs/_core/hw/__init__.pyi

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,8 @@ __all__ = [
2121
"FrankaHand",
2222
"IKSolver",
2323
"exceptions",
24-
"franka",
25-
"rcs",
24+
"franka_ik",
25+
"rcs_ik",
2626
]
2727

2828
class FHConfig(rcs._core.common.GripperConfig):
@@ -111,16 +111,16 @@ class IKSolver:
111111
"""
112112
Members:
113113
114-
franka
114+
franka_ik
115115
116-
rcs
116+
rcs_ik
117117
"""
118118

119119
__members__: typing.ClassVar[
120120
dict[str, IKSolver]
121-
] # value = {'franka': <IKSolver.franka: 0>, 'rcs': <IKSolver.rcs: 1>}
122-
franka: typing.ClassVar[IKSolver] # value = <IKSolver.franka: 0>
123-
rcs: typing.ClassVar[IKSolver] # value = <IKSolver.rcs: 1>
121+
] # value = {'franka_ik': <IKSolver.franka_ik: 0>, 'rcs_ik': <IKSolver.rcs_ik: 1>}
122+
franka_ik: typing.ClassVar[IKSolver] # value = <IKSolver.franka_ik: 0>
123+
rcs_ik: typing.ClassVar[IKSolver] # value = <IKSolver.rcs_ik: 1>
124124
def __eq__(self, other: typing.Any) -> bool: ...
125125
def __getstate__(self) -> int: ...
126126
def __hash__(self) -> int: ...
@@ -136,5 +136,5 @@ class IKSolver:
136136
@property
137137
def value(self) -> int: ...
138138

139-
franka: IKSolver # value = <IKSolver.franka: 0>
140-
rcs: IKSolver # value = <IKSolver.rcs: 1>
139+
franka_ik: IKSolver # value = <IKSolver.franka_ik: 0>
140+
rcs_ik: IKSolver # value = <IKSolver.rcs_ik: 1>

python/rcs/control/fr3_desk.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ def home(ip: str, username: str, password: str, shut: bool, unlock: bool = False
4040
f = rcs.hw.FR3(ip)
4141
config = rcs.hw.FR3Config()
4242
config.speed_factor = 0.2
43-
config.ik_solver = rcs.hw.IKSolver.franka
43+
config.ik_solver = rcs.hw.IKSolver.franka_ik
4444
f.set_parameters(config)
4545
config_hand = rcs.hw.FHConfig()
4646
g = rcs.hw.FrankaHand(ip, config_hand)

python/rcs/envs/utils.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ def default_fr3_hw_robot_cfg(async_control: bool = False):
2727
robot_cfg = FR3Config()
2828
robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
2929
robot_cfg.speed_factor = 0.1
30-
robot_cfg.ik_solver = IKSolver.rcs
30+
robot_cfg.ik_solver = IKSolver.rcs_ik
3131
robot_cfg.async_control = async_control
3232
return robot_cfg
3333

src/hw/FR3.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -669,13 +669,13 @@ void FR3::set_cartesian_position(const common::Pose &x) {
669669
// nominal end effector frame should be on top of tcp offset as franka already
670670
// takes care of the default franka hand offset lets add a franka hand offset
671671

672-
if (this->cfg.ik_solver == IKSolver::franka) {
672+
if (this->cfg.ik_solver == IKSolver::franka_ik) {
673673
// if gripper is attached the tcp offset will automatically be applied
674674
// by libfranka
675675
this->robot.setEE(nominal_end_effector_frame_value.affine_array());
676676
this->set_cartesian_position_internal(x, 1.0, std::nullopt, std::nullopt);
677677

678-
} else if (this->cfg.ik_solver == IKSolver::rcs) {
678+
} else if (this->cfg.ik_solver == IKSolver::rcs_ik) {
679679
this->set_cartesian_position_ik(x);
680680
}
681681
}

src/hw/FR3.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,15 +25,15 @@ struct FR3Load {
2525
std::optional<Eigen::Vector3d> f_x_cload;
2626
std::optional<Eigen::Matrix3d> load_inertia;
2727
};
28-
enum IKSolver { franka = 0, rcs };
28+
enum IKSolver { franka_ik = 0, rcs_ik };
2929
// modes: joint-space control, operational-space control, zero-torque
3030
// control
3131
enum Controller { none = 0, jsc, osc, ztc };
3232
struct FR3Config : common::RobotConfig {
3333
// TODO: max force and elbow?
3434
// TODO: we can either write specific bindings for each, or we use python
3535
// dictionaries with these objects
36-
IKSolver ik_solver = IKSolver::franka;
36+
IKSolver ik_solver = IKSolver::franka_ik;
3737
double speed_factor = DEFAULT_SPEED_FACTOR;
3838
std::optional<FR3Load> load_parameters = std::nullopt;
3939
std::optional<common::Pose> nominal_end_effector_frame = std::nullopt;

src/pybind/rcs.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -304,8 +304,8 @@ PYBIND11_MODULE(_core, m) {
304304
.def_readwrite("load_inertia", &rcs::hw::FR3Load::load_inertia);
305305

306306
py::enum_<rcs::hw::IKSolver>(hw, "IKSolver")
307-
.value("franka", rcs::hw::IKSolver::franka)
308-
.value("rcs", rcs::hw::IKSolver::rcs)
307+
.value("franka_ik", rcs::hw::IKSolver::franka_ik)
308+
.value("rcs_ik", rcs::hw::IKSolver::rcs_ik)
309309
.export_values();
310310

311311
py::class_<rcs::hw::FR3Config, rcs::common::RobotConfig>(hw, "FR3Config")

0 commit comments

Comments
 (0)