Skip to content

Commit 6c9c740

Browse files
committed
refactor!: device ids are now passed through the config
- the config for each device must now hold its id e.g. its ip address instead of explicitly passing it - robotiqgripper in the UR5e extension now has its own config
1 parent 66d4988 commit 6c9c740

27 files changed

Lines changed: 202 additions & 162 deletions

File tree

examples/fr3/fr3_direct_control.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -99,19 +99,20 @@ def main():
9999
else:
100100
fr3_cfg = default_fr3_hw_robot_cfg()
101101
fr3_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
102+
fr3_cfg.ip = ROBOT_IP
102103
ik = rcs.common.Pin(
103104
fr3_cfg.kinematic_model_path,
104105
fr3_cfg.attachment_site,
105106
urdf=fr3_cfg.kinematic_model_path.endswith(".urdf"),
106107
)
107-
robot = hw.Franka(ROBOT_IP, ik)
108-
robot.set_config(fr3_cfg) # type: ignore
108+
robot = hw.Franka(fr3_cfg, ik)
109109

110110
gripper_cfg_hw = hw.FHConfig()
111111
gripper_cfg_hw.epsilon_inner = gripper_cfg_hw.epsilon_outer = 0.1
112112
gripper_cfg_hw.speed = 0.1
113113
gripper_cfg_hw.force = 30
114-
gripper = hw.FrankaHand(ROBOT_IP, gripper_cfg_hw)
114+
gripper_cfg_hw.ip = ROBOT_IP
115+
gripper = hw.FrankaHand(gripper_cfg_hw)
115116
input("the robot is going to move, press enter whenever you are ready")
116117

117118
# move to home position and open gripper

examples/ur5e/ur5e_env_cartesian_control.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,11 @@
2020

2121
def main():
2222
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
23-
robot_cfg = UR5eConfig()
23+
robot_cfg = UR5eConfig(ip=ROBOT_IP)
2424
robot_cfg.async_control = False
2525
env_rel = RCSUR5eEnvCreator()(
2626
robot_cfg=robot_cfg,
2727
control_mode=ControlMode.CARTESIAN_TQuat,
28-
ip=ROBOT_IP,
2928
camera_set=None,
3029
max_relative_movement=0.2,
3130
relative_to=RelativeTo.LAST_STEP,

examples/ur5e/ur5e_env_joint_control.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,10 @@
2222
def main():
2323

2424
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
25-
robot_cfg = UR5eConfig()
25+
robot_cfg = UR5eConfig(ip=ROBOT_IP)
2626
env_rel = RCSUR5eEnvCreator()(
2727
control_mode=ControlMode.JOINTS,
2828
robot_cfg=robot_cfg,
29-
ip=ROBOT_IP,
3029
camera_set=None,
3130
max_relative_movement=np.deg2rad(5),
3231
relative_to=RelativeTo.LAST_STEP,

examples/xarm7/xarm7_env_cartesian_control.py

Lines changed: 13 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
from rcs.envs.base import ControlMode, RelativeTo
66
from rcs.envs.creators import SimEnvCreator
77
from rcs_xarm7.creators import RCSXArm7EnvCreator
8+
from rcs_xarm7.hw import XArm7Config
89

910
import rcs
1011
from rcs import sim
@@ -30,15 +31,16 @@
3031
def main():
3132

3233
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
34+
robot_cfg = XArm7Config(ip=ROBOT_IP)
3335
env_rel = RCSXArm7EnvCreator()(
36+
robot_cfg=robot_cfg,
3437
control_mode=ControlMode.CARTESIAN_TQuat,
35-
ip=ROBOT_IP,
3638
relative_to=RelativeTo.LAST_STEP,
3739
max_relative_movement=0.5,
3840
)
3941
else:
40-
robot_cfg = sim.SimRobotConfig()
41-
robot_cfg.actuators = [
42+
robot_sim_cfg = sim.SimRobotConfig()
43+
robot_sim_cfg.actuators = [
4244
"act1",
4345
"act2",
4446
"act3",
@@ -47,7 +49,7 @@ def main():
4749
"act6",
4850
"act7",
4951
]
50-
robot_cfg.joints = [
52+
robot_sim_cfg.joints = [
5153
"joint1",
5254
"joint2",
5355
"joint3",
@@ -56,15 +58,15 @@ def main():
5658
"joint6",
5759
"joint7",
5860
]
59-
robot_cfg.base = "base"
60-
robot_cfg.robot_type = rcs.common.RobotType.XArm7
61-
robot_cfg.attachment_site = "attachment_site"
62-
robot_cfg.arm_collision_geoms = []
61+
robot_sim_cfg.base = "base"
62+
robot_sim_cfg.robot_type = rcs.common.RobotType.XArm7
63+
robot_sim_cfg.attachment_site = "attachment_site"
64+
robot_sim_cfg.arm_collision_geoms = []
6365
scene = rcs.scenes["xarm7_empty_world"]
64-
robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene
65-
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
66+
robot_sim_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene
67+
robot_sim_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
6668
env_rel = SimEnvCreator()(
67-
robot_cfg=robot_cfg,
69+
robot_cfg=robot_sim_cfg,
6870
control_mode=ControlMode.CARTESIAN_TQuat,
6971
gripper_cfg=None,
7072
# cameras=default_mujoco_cameraset_cfg(),

examples/xarm7/xarm7_env_joint_control.py

Lines changed: 13 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
from rcs.envs.base import ControlMode, RelativeTo
77
from rcs.envs.creators import SimEnvCreator
88
from rcs_xarm7.creators import RCSXArm7EnvCreator
9+
from rcs_xarm7.hw import XArm7Config
910

1011
import rcs
1112
from rcs import sim
@@ -30,15 +31,16 @@
3031

3132
def main():
3233
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
34+
robot_cfg = XArm7Config(ip=ROBOT_IP)
3335
env_rel = RCSXArm7EnvCreator()(
36+
robot_cfg=robot_cfg,
3437
control_mode=ControlMode.JOINTS,
35-
ip=ROBOT_IP,
3638
relative_to=RelativeTo.LAST_STEP,
3739
max_relative_movement=np.deg2rad(5),
3840
)
3941
else:
40-
robot_cfg = sim.SimRobotConfig()
41-
robot_cfg.actuators = [
42+
robot_sim_cfg = sim.SimRobotConfig()
43+
robot_sim_cfg.actuators = [
4244
"act1",
4345
"act2",
4446
"act3",
@@ -47,7 +49,7 @@ def main():
4749
"act6",
4850
"act7",
4951
]
50-
robot_cfg.joints = [
52+
robot_sim_cfg.joints = [
5153
"joint1",
5254
"joint2",
5355
"joint3",
@@ -56,15 +58,15 @@ def main():
5658
"joint6",
5759
"joint7",
5860
]
59-
robot_cfg.base = "base"
60-
robot_cfg.robot_type = rcs.common.RobotType.XArm7
61-
robot_cfg.attachment_site = "attachment_site"
62-
robot_cfg.arm_collision_geoms = []
61+
robot_sim_cfg.base = "base"
62+
robot_sim_cfg.robot_type = rcs.common.RobotType.XArm7
63+
robot_sim_cfg.attachment_site = "attachment_site"
64+
robot_sim_cfg.arm_collision_geoms = []
6365
scene = rcs.scenes["xarm7_empty_world"]
64-
robot_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene
65-
robot_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
66+
robot_sim_cfg.mjcf_scene_path = scene.mjb or scene.mjcf_scene
67+
robot_sim_cfg.kinematic_model_path = rcs.scenes["xarm7_empty_world"].mjcf_robot
6668
env_rel = SimEnvCreator()(
67-
robot_cfg=robot_cfg,
69+
robot_cfg=robot_sim_cfg,
6870
control_mode=ControlMode.JOINTS,
6971
gripper_cfg=None,
7072
# cameras=default_mujoco_cameraset_cfg(),

extensions/rcs_fr3/src/hw/Franka.cpp

Lines changed: 26 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -19,17 +19,15 @@
1919

2020
namespace rcs {
2121
namespace hw {
22-
Franka::Franka(const std::string& ip,
23-
std::optional<std::shared_ptr<common::Kinematics>> ik,
24-
const std::optional<FrankaConfig>& cfg)
25-
: robot(ip), m_ik(ik) {
22+
Franka::Franka(const FrankaConfig& cfg,
23+
std::optional<std::shared_ptr<common::Kinematics>> ik)
24+
: m_cfg(cfg),
25+
m_ik(ik),
26+
robot(cfg.ip, cfg.ignore_realtime ? franka::RealtimeConfig::kIgnore
27+
: franka::RealtimeConfig::kEnforce) {
2628
// set collision behavior and impedance
2729
this->set_default_robot_behavior();
2830
this->set_guiding_mode(true, true, true, true, true, true, true);
29-
30-
if (cfg.has_value()) {
31-
this->cfg = cfg.value();
32-
} // else default constructor
3331
}
3432

3533
Franka::~Franka() {
@@ -46,11 +44,11 @@ Franka::~Franka() {
4644
* otherwise the call will fail
4745
*/
4846
bool Franka::set_config(const FrankaConfig& cfg) {
49-
this->cfg = cfg;
50-
this->cfg.speed_factor = std::min(std::max(cfg.speed_factor, 0.0), 1.0);
47+
this->m_cfg = cfg;
48+
this->m_cfg.speed_factor = std::min(std::max(cfg.speed_factor, 0.0), 1.0);
5149

52-
if (this->cfg.load_parameters.has_value()) {
53-
auto load_value = &(this->cfg.load_parameters.value());
50+
if (this->m_cfg.load_parameters.has_value()) {
51+
auto load_value = &(this->m_cfg.load_parameters.value());
5452
if (!load_value->f_x_cload.has_value()) {
5553
load_value->f_x_cload = Eigen::Vector3d::Zero();
5654
}
@@ -69,7 +67,7 @@ bool Franka::set_config(const FrankaConfig& cfg) {
6967
FrankaConfig* Franka::get_config() {
7068
// copy config to heap
7169
FrankaConfig* cfg = new FrankaConfig();
72-
*cfg = this->cfg;
70+
*cfg = this->m_cfg;
7371
return cfg;
7472
}
7573

@@ -110,19 +108,19 @@ common::Pose Franka::get_cartesian_position() {
110108
x = common::Pose(this->curr_state.O_T_EE);
111109
this->interpolator_mutex.unlock();
112110
}
113-
if (!this->cfg.tcp_offset_configured_in_desk) {
114-
return x * cfg.tcp_offset;
111+
if (!this->m_cfg.tcp_offset_configured_in_desk) {
112+
return x * this->m_cfg.tcp_offset;
115113
}
116114
return x;
117115
}
118116

119117
void Franka::set_joint_position(const common::VectorXd& q) {
120-
if (this->cfg.async_control) {
118+
if (this->m_cfg.async_control) {
121119
this->controller_set_joint_position(q);
122120
return;
123121
}
124122
// sync control
125-
FrankaMotionGenerator motion_generator(this->cfg.speed_factor, q);
123+
FrankaMotionGenerator motion_generator(this->m_cfg.speed_factor, q);
126124
this->robot.control(motion_generator);
127125
}
128126

@@ -635,8 +633,8 @@ void Franka::move_home() {
635633
// sync
636634
this->stop_control_thread();
637635
FrankaMotionGenerator motion_generator(
638-
this->cfg.speed_factor,
639-
common::robots_meta_config.at(this->cfg.robot_type).q_home);
636+
this->m_cfg.speed_factor,
637+
common::robots_meta_config.at(this->m_cfg.robot_type).q_home);
640638
this->robot.control(motion_generator);
641639
}
642640

@@ -713,28 +711,28 @@ std::optional<std::shared_ptr<common::Kinematics>> Franka::get_ik() {
713711

714712
void Franka::set_cartesian_position(const common::Pose& x) {
715713
// pose is assumed to be in the robots coordinate frame
716-
if (this->cfg.async_control) {
714+
if (this->m_cfg.async_control) {
717715
this->osc_set_cartesian_position(x);
718716
return;
719717
}
720718
// TODO: this should handled with tcp offset config
721719
common::Pose nominal_end_effector_frame_value;
722-
if (this->cfg.nominal_end_effector_frame.has_value()) {
720+
if (this->m_cfg.nominal_end_effector_frame.has_value()) {
723721
nominal_end_effector_frame_value =
724-
this->cfg.nominal_end_effector_frame.value();
722+
this->m_cfg.nominal_end_effector_frame.value();
725723
} else {
726724
nominal_end_effector_frame_value = common::Pose::Identity();
727725
}
728726
// nominal end effector frame should be on top of tcp offset as franka already
729727
// takes care of the default franka hand offset lets add a franka hand offset
730728

731-
if (this->cfg.ik_solver == IKSolver::franka_ik) {
729+
if (this->m_cfg.ik_solver == IKSolver::franka_ik) {
732730
// if gripper is attached the tcp offset will automatically be applied
733731
// by libfranka
734732
this->robot.setEE(nominal_end_effector_frame_value.affine_array());
735733
this->set_cartesian_position_internal(x, 1.0, std::nullopt, std::nullopt);
736734

737-
} else if (this->cfg.ik_solver == IKSolver::rcs_ik) {
735+
} else if (this->m_cfg.ik_solver == IKSolver::rcs_ik) {
738736
this->set_cartesian_position_ik(x);
739737
}
740738
}
@@ -746,7 +744,7 @@ void Franka::set_cartesian_position_ik(const common::Pose& pose) {
746744
"position.");
747745
}
748746
auto joints = this->m_ik.value()->inverse(pose, this->get_joint_position(),
749-
this->cfg.tcp_offset);
747+
this->m_cfg.tcp_offset);
750748

751749
if (joints.has_value()) {
752750
this->set_joint_position(joints.value());
@@ -758,8 +756,9 @@ void Franka::set_cartesian_position_ik(const common::Pose& pose) {
758756
}
759757

760758
common::Pose Franka::get_base_pose_in_world_coordinates() {
761-
return this->cfg.world_to_robot.has_value() ? this->cfg.world_to_robot.value()
762-
: common::Pose();
759+
return this->m_cfg.world_to_robot.has_value()
760+
? this->m_cfg.world_to_robot.value()
761+
: common::Pose();
763762
}
764763

765764
void Franka::set_cartesian_position_internal(const common::Pose& pose,

extensions/rcs_fr3/src/hw/Franka.h

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@ struct FrankaConfig : common::RobotConfig {
4444
std::optional<common::Pose> world_to_robot = std::nullopt;
4545
bool async_control = false;
4646
bool tcp_offset_configured_in_desk = true;
47+
bool ignore_realtime = false;
48+
std::string ip;
4749
};
4850

4951
struct FR3Config : FrankaConfig {};
@@ -58,7 +60,7 @@ struct FrankaState : common::RobotState {
5860
class Franka : public common::Robot {
5961
private:
6062
franka::Robot robot;
61-
FrankaConfig cfg;
63+
FrankaConfig m_cfg;
6264
std::optional<std::shared_ptr<common::Kinematics>> m_ik;
6365
std::optional<std::thread> control_thread = std::nullopt;
6466
common::LinearPoseTrajInterpolator traj_interpolator;
@@ -75,9 +77,8 @@ class Franka : public common::Robot {
7577
void check_for_background_errors();
7678

7779
public:
78-
Franka(const std::string& ip,
79-
std::optional<std::shared_ptr<common::Kinematics>> ik = std::nullopt,
80-
const std::optional<FrankaConfig>& cfg = std::nullopt);
80+
Franka(const FrankaConfig& cfg,
81+
std::optional<std::shared_ptr<common::Kinematics>> ik = std::nullopt);
8182
~Franka() override;
8283

8384
bool set_config(const FrankaConfig& cfg);

0 commit comments

Comments
 (0)