diff --git a/examples/fr3/fr3_direct_control.py b/examples/fr3/fr3_direct_control.py index b7be3c04..c32c42ea 100644 --- a/examples/fr3/fr3_direct_control.py +++ b/examples/fr3/fr3_direct_control.py @@ -98,7 +98,7 @@ def main(): robot_cfg = hw.FR3Config() robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset()) robot_cfg.ik_solver = hw.IKSolver.rcs_ik - robot.set_parameters(robot_cfg) # type: ignore + robot.set_config(robot_cfg) # type: ignore gripper_cfg_hw = hw.FHConfig() gripper_cfg_hw.epsilon_inner = gripper_cfg_hw.epsilon_outer = 0.1 diff --git a/extensions/rcs_fr3/README.md b/extensions/rcs_fr3/README.md index ae6993f4..54a89e01 100644 --- a/extensions/rcs_fr3/README.md +++ b/extensions/rcs_fr3/README.md @@ -25,7 +25,7 @@ with FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False): robot_cfg = FR3Config() robot_cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset()) robot_cfg.ik_solver = IKSolver.rcs_ik - robot.set_parameters(robot_cfg) + robot.set_config(robot_cfg) gripper_cfg_hw = hw.FHConfig() gripper_cfg_hw.epsilon_inner = gripper_cfg_hw.epsilon_outer = 0.1 diff --git a/extensions/rcs_fr3/src/hw/FR3.cpp b/extensions/rcs_fr3/src/hw/FR3.cpp index 256d7dbf..73222ba7 100644 --- a/extensions/rcs_fr3/src/hw/FR3.cpp +++ b/extensions/rcs_fr3/src/hw/FR3.cpp @@ -38,7 +38,7 @@ FR3::~FR3() {} * @param cfg The configuration for the robot, it should be a FR3Config type * otherwise the call will fail */ -bool FR3::set_parameters(const FR3Config &cfg) { +bool FR3::set_config(const FR3Config &cfg) { this->cfg = cfg; this->cfg.speed_factor = std::min(std::max(cfg.speed_factor, 0.0), 1.0); @@ -59,7 +59,7 @@ bool FR3::set_parameters(const FR3Config &cfg) { return true; } -FR3Config *FR3::get_parameters() { +FR3Config *FR3::get_config() { // copy config to heap FR3Config *cfg = new FR3Config(); *cfg = this->cfg; diff --git a/extensions/rcs_fr3/src/hw/FR3.h b/extensions/rcs_fr3/src/hw/FR3.h index 7197f569..71d9091e 100644 --- a/extensions/rcs_fr3/src/hw/FR3.h +++ b/extensions/rcs_fr3/src/hw/FR3.h @@ -66,9 +66,9 @@ class FR3 : public common::Robot { const std::optional &cfg = std::nullopt); ~FR3() override; - bool set_parameters(const FR3Config &cfg); + bool set_config(const FR3Config &cfg); - FR3Config *get_parameters() override; + FR3Config *get_config() override; FR3State *get_state() override; diff --git a/extensions/rcs_fr3/src/hw/FrankaHand.cpp b/extensions/rcs_fr3/src/hw/FrankaHand.cpp index b4868adb..501f55af 100644 --- a/extensions/rcs_fr3/src/hw/FrankaHand.cpp +++ b/extensions/rcs_fr3/src/hw/FrankaHand.cpp @@ -20,7 +20,7 @@ FrankaHand::FrankaHand(const std::string &ip, const FHConfig &cfg) FrankaHand::~FrankaHand() {} -bool FrankaHand::set_parameters(const FHConfig &cfg) { +bool FrankaHand::set_config(const FHConfig &cfg) { franka::GripperState gripper_state = this->gripper.readOnce(); if (gripper_state.max_width < cfg.grasping_width) { return false; @@ -29,7 +29,7 @@ bool FrankaHand::set_parameters(const FHConfig &cfg) { return true; } -FHConfig *FrankaHand::get_parameters() { +FHConfig *FrankaHand::get_config() { // copy config to heap FHConfig *cfg = new FHConfig(); *cfg = this->cfg; diff --git a/extensions/rcs_fr3/src/hw/FrankaHand.h b/extensions/rcs_fr3/src/hw/FrankaHand.h index 7de4753d..6a9f3bc0 100644 --- a/extensions/rcs_fr3/src/hw/FrankaHand.h +++ b/extensions/rcs_fr3/src/hw/FrankaHand.h @@ -57,9 +57,9 @@ class FrankaHand : public common::Gripper { FrankaHand(const std::string &ip, const FHConfig &cfg); ~FrankaHand() override; - bool set_parameters(const FHConfig &cfg); + bool set_config(const FHConfig &cfg); - FHConfig *get_parameters() override; + FHConfig *get_config() override; FHState *get_state() override; diff --git a/extensions/rcs_fr3/src/pybind/rcs.cpp b/extensions/rcs_fr3/src/pybind/rcs.cpp index e5fefcfa..f626e082 100644 --- a/extensions/rcs_fr3/src/pybind/rcs.cpp +++ b/extensions/rcs_fr3/src/pybind/rcs.cpp @@ -101,8 +101,8 @@ PYBIND11_MODULE(_core, m) { .def(py::init>>(), py::arg("ip"), py::arg("ik") = std::nullopt) - .def("set_parameters", &rcs::hw::FR3::set_parameters, py::arg("cfg")) - .def("get_parameters", &rcs::hw::FR3::get_parameters) + .def("set_config", &rcs::hw::FR3::set_config, py::arg("cfg")) + .def("get_config", &rcs::hw::FR3::get_config) .def("get_state", &rcs::hw::FR3::get_state) .def("set_default_robot_behavior", &rcs::hw::FR3::set_default_robot_behavior) @@ -132,10 +132,9 @@ PYBIND11_MODULE(_core, m) { hw, "FrankaHand", gripper) .def(py::init(), py::arg("ip"), py::arg("cfg")) - .def("get_parameters", &rcs::hw::FrankaHand::get_parameters) + .def("get_config", &rcs::hw::FrankaHand::get_config) .def("get_state", &rcs::hw::FrankaHand::get_state) - .def("set_parameters", &rcs::hw::FrankaHand::set_parameters, - py::arg("cfg")) + .def("set_config", &rcs::hw::FrankaHand::set_config, py::arg("cfg")) .def("is_grasped", &rcs::hw::FrankaHand::is_grasped) .def("homing", &rcs::hw::FrankaHand::homing); diff --git a/extensions/rcs_fr3/src/rcs_fr3/_core/hw/__init__.pyi b/extensions/rcs_fr3/src/rcs_fr3/_core/hw/__init__.pyi index c2311b46..b61f38bb 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/_core/hw/__init__.pyi +++ b/extensions/rcs_fr3/src/rcs_fr3/_core/hw/__init__.pyi @@ -58,13 +58,14 @@ class FR3(rcs._core.common.Robot): self, desired_q: numpy.ndarray[tuple[typing.Literal[7]], numpy.dtype[numpy.float64]] ) -> None: ... def double_tap_robot_to_continue(self) -> None: ... - def get_parameters(self) -> FR3Config: ... + def get_config(self) -> FR3Config: ... def get_state(self) -> FR3State: ... def osc_set_cartesian_position(self, desired_pos_EE_in_base_frame: rcs._core.common.Pose) -> None: ... def set_cartesian_position_ik( self, pose: rcs._core.common.Pose, max_time: float, elbow: float | None, max_force: float | None = 5 ) -> None: ... def set_cartesian_position_internal(self, pose: rcs._core.common.Pose) -> None: ... + def set_config(self, cfg: FR3Config) -> bool: ... def set_default_robot_behavior(self) -> None: ... def set_guiding_mode( self, @@ -76,7 +77,6 @@ class FR3(rcs._core.common.Robot): yaw: bool = True, elbow: bool = True, ) -> None: ... - def set_parameters(self, cfg: FR3Config) -> bool: ... def stop_control_thread(self) -> None: ... def zero_torque_guiding(self) -> None: ... @@ -100,11 +100,11 @@ class FR3State(rcs._core.common.RobotState): class FrankaHand(rcs._core.common.Gripper): def __init__(self, ip: str, cfg: FHConfig) -> None: ... - def get_parameters(self) -> FHConfig: ... + def get_config(self) -> FHConfig: ... def get_state(self) -> FHState: ... def homing(self) -> bool: ... def is_grasped(self) -> bool: ... - def set_parameters(self, cfg: FHConfig) -> bool: ... + def set_config(self, cfg: FHConfig) -> bool: ... class IKSolver: """ diff --git a/extensions/rcs_fr3/src/rcs_fr3/creators.py b/extensions/rcs_fr3/src/rcs_fr3/creators.py index 2c05b60e..5dbbd35d 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/creators.py +++ b/extensions/rcs_fr3/src/rcs_fr3/creators.py @@ -64,7 +64,7 @@ def __call__( # type: ignore urdf_path = rcs.scenes["fr3_empty_world"].urdf ik = rcs.common.RL(str(urdf_path)) if urdf_path is not None else None robot = hw.FR3(ip, ik) - robot.set_parameters(robot_cfg) + robot.set_config(robot_cfg) env: gym.Env = RobotEnv(robot, ControlMode.JOINTS if collision_guard is not None else control_mode) @@ -119,7 +119,7 @@ def __call__( # type: ignore robots: dict[str, hw.FR3] = {} for ip in ips: robots[ip] = hw.FR3(ip, ik) - robots[ip].set_parameters(robot_cfg) + robots[ip].set_config(robot_cfg) envs = {} for ip in ips: diff --git a/extensions/rcs_fr3/src/rcs_fr3/desk.py b/extensions/rcs_fr3/src/rcs_fr3/desk.py index ab5076f6..049b8502 100644 --- a/extensions/rcs_fr3/src/rcs_fr3/desk.py +++ b/extensions/rcs_fr3/src/rcs_fr3/desk.py @@ -41,7 +41,7 @@ def home(ip: str, username: str, password: str, shut: bool, unlock: bool = False config = rcs_fr3.hw.FR3Config() config.speed_factor = 0.2 config.ik_solver = rcs_fr3.hw.IKSolver.franka_ik - f.set_parameters(config) + f.set_config(config) config_hand = rcs_fr3.hw.FHConfig() g = rcs_fr3.hw.FrankaHand(ip, config_hand) if shut: @@ -55,7 +55,7 @@ def info(ip: str, username: str, password: str, include_hand: bool = False): with Desk.fci(ip, username, password): f = rcs_fr3.hw.FR3(ip) config = rcs_fr3.hw.FR3Config() - f.set_parameters(config) + f.set_config(config) print("Robot info:") print("Current cartesian position:") print(f.get_cartesian_position()) diff --git a/extensions/rcs_so101/src/rcs_so101/hw.py b/extensions/rcs_so101/src/rcs_so101/hw.py index ec9644f5..581f1555 100644 --- a/extensions/rcs_so101/src/rcs_so101/hw.py +++ b/extensions/rcs_so101/src/rcs_so101/hw.py @@ -35,7 +35,7 @@ def get_joint_position(self) -> np.ndarray[tuple[typing.Literal[5]], np.dtype[np ), ) - def get_parameters(self): + def get_config(self): a = common.RobotConfig() a.robot_platform = common.RobotPlatform.HARDWARE a.robot_type = common.RobotType.SO101 @@ -83,7 +83,7 @@ def get_normalized_width(self) -> float: obs = self._hf_robot.get_observation() return obs["gripper.pos"] / 100.0 - # def get_parameters(self) -> GripperConfig: ... + # def get_config(self) -> GripperConfig: ... # def get_state(self) -> GripperState: ... def grasp(self) -> None: diff --git a/extensions/rcs_xarm7/src/rcs_xarm7/hw.py b/extensions/rcs_xarm7/src/rcs_xarm7/hw.py index e818e9c2..49c1bf93 100644 --- a/extensions/rcs_xarm7/src/rcs_xarm7/hw.py +++ b/extensions/rcs_xarm7/src/rcs_xarm7/hw.py @@ -61,10 +61,10 @@ def get_joint_position(self) -> np.ndarray[tuple[typing.Literal[7]], np.dtype[np np.array(self._xarm.get_servo_angle(is_radian=True)[1]), ) - def get_parameters(self) -> XArm7Config: + def get_config(self) -> XArm7Config: return self._config - def set_parameters(self, robot_cfg: XArm7Config) -> None: + def set_config(self, robot_cfg: XArm7Config) -> None: self._config = robot_cfg def get_state(self) -> common.RobotState: diff --git a/include/rcs/Robot.h b/include/rcs/Robot.h index 4277bda5..f8ab00c6 100644 --- a/include/rcs/Robot.h +++ b/include/rcs/Robot.h @@ -128,13 +128,13 @@ class Robot { public: virtual ~Robot(){}; - // Also add an implementation specific set_parameters function that takes + // Also add an implementation specific set_config function that takes // a deduced config type - // This functino can also be used for signaling e.g. error recovery and the + // This function can also be used for signaling e.g. error recovery and the // like - // bool set_parameters(const RConfig& cfg); + // bool set_config(const RConfig& cfg); - virtual RobotConfig* get_parameters() = 0; + virtual RobotConfig* get_config() = 0; virtual RobotState* get_state() = 0; @@ -167,11 +167,11 @@ class Gripper { public: virtual ~Gripper(){}; - // Also add an implementation specific set_parameters function that takes + // Also add an implementation specific set_config function that takes // a deduced config type - // bool set_parameters(const GConfig& cfg); + // bool set_config(const GConfig& cfg); - virtual GripperConfig* get_parameters() = 0; + virtual GripperConfig* get_config() = 0; virtual GripperState* get_state() = 0; // set width of the gripper, 0 is closed, 1 is open @@ -200,11 +200,11 @@ class Hand { public: virtual ~Hand(){}; // TODO: Add low-level control interface for the hand with internal state updates - // Also add an implementation specific set_parameters function that takes + // Also add an implementation specific set_config function that takes // a deduced config type - // bool set_parameters(const GConfig& cfg); + // bool set_config(const GConfig& cfg); - virtual HandConfig* get_parameters() = 0; + virtual HandConfig* get_config() = 0; virtual HandState* get_state() = 0; // set width of the hand, 0 is closed, 1 is open diff --git a/python/rcs/_core/common.pyi b/python/rcs/_core/common.pyi index 8da2e256..590b34a4 100644 --- a/python/rcs/_core/common.pyi +++ b/python/rcs/_core/common.pyi @@ -93,8 +93,8 @@ class GraspType: class Gripper: def __init__(self) -> None: ... def close(self) -> None: ... + def get_config(self) -> GripperConfig: ... def get_normalized_width(self) -> float: ... - def get_parameters(self) -> GripperConfig: ... def get_state(self) -> GripperState: ... def grasp(self) -> None: ... def is_grasped(self) -> bool: ... @@ -112,8 +112,8 @@ class GripperState: class Hand: def __init__(self) -> None: ... def close(self) -> None: ... + def get_config(self) -> HandConfig: ... def get_normalized_joint_poses(self) -> numpy.ndarray[tuple[M], numpy.dtype[numpy.float64]]: ... - def get_parameters(self) -> HandConfig: ... def get_state(self) -> HandState: ... def grasp(self) -> None: ... def is_grasped(self) -> bool: ... @@ -222,9 +222,9 @@ class Robot: def close(self) -> None: ... def get_base_pose_in_world_coordinates(self) -> Pose: ... def get_cartesian_position(self) -> Pose: ... + def get_config(self) -> RobotConfig: ... def get_ik(self) -> IK | None: ... def get_joint_position(self) -> numpy.ndarray[tuple[M], numpy.dtype[numpy.float64]]: ... - def get_parameters(self) -> RobotConfig: ... def get_state(self) -> RobotState: ... def move_home(self) -> None: ... def reset(self) -> None: ... diff --git a/python/rcs/_core/sim.pyi b/python/rcs/_core/sim.pyi index 07b172c7..9ac55a03 100644 --- a/python/rcs/_core/sim.pyi +++ b/python/rcs/_core/sim.pyi @@ -118,9 +118,9 @@ class SimConfig: class SimGripper(rcs._core.common.Gripper): def __init__(self, sim: Sim, cfg: SimGripperConfig) -> None: ... - def get_parameters(self) -> SimGripperConfig: ... + def get_config(self) -> SimGripperConfig: ... def get_state(self) -> SimGripperState: ... - def set_parameters(self, cfg: SimGripperConfig) -> bool: ... + def set_config(self, cfg: SimGripperConfig) -> bool: ... class SimGripperConfig(rcs._core.common.GripperConfig): actuator: str @@ -153,10 +153,10 @@ class SimRobot(rcs._core.common.Robot): def __init__( self, sim: Sim, ik: rcs._core.common.IK, cfg: SimRobotConfig, register_convergence_callback: bool = True ) -> None: ... - def get_parameters(self) -> SimRobotConfig: ... + def get_config(self) -> SimRobotConfig: ... def get_state(self) -> SimRobotState: ... + def set_config(self, cfg: SimRobotConfig) -> bool: ... def set_joints_hard(self, q: numpy.ndarray[tuple[M], numpy.dtype[numpy.float64]]) -> None: ... - def set_parameters(self, cfg: SimRobotConfig) -> bool: ... class SimRobotConfig(rcs._core.common.RobotConfig): actuators: list[str] @@ -190,9 +190,9 @@ class SimRobotState(rcs._core.common.RobotState): class SimTilburgHand(rcs._core.common.Hand): def __init__(self, sim: Sim, cfg: SimTilburgHandConfig) -> None: ... - def get_parameters(self) -> SimTilburgHandConfig: ... + def get_config(self) -> SimTilburgHandConfig: ... def get_state(self) -> SimTilburgHandState: ... - def set_parameters(self, cfg: SimTilburgHandConfig) -> bool: ... + def set_config(self, cfg: SimTilburgHandConfig) -> bool: ... class SimTilburgHandConfig(rcs._core.common.HandConfig): actuators: list[str] diff --git a/python/rcs/envs/base.py b/python/rcs/envs/base.py index 288438f6..7c745e1e 100644 --- a/python/rcs/envs/base.py +++ b/python/rcs/envs/base.py @@ -176,7 +176,7 @@ class ControlMode(Enum): def get_dof(robot: common.Robot) -> int: """Returns the number of degrees of freedom of the robot.""" - return common.robots_meta_config(robot.get_parameters().robot_type).dof + return common.robots_meta_config(robot.get_config().robot_type).dof def get_joint_limits(robot: common.Robot) -> tuple[np.ndarray, np.ndarray]: @@ -184,13 +184,13 @@ def get_joint_limits(robot: common.Robot) -> tuple[np.ndarray, np.ndarray]: The first element is the lower limit, the second element is the upper limit. """ - limits = common.robots_meta_config(robot.get_parameters().robot_type).joint_limits + limits = common.robots_meta_config(robot.get_config().robot_type).joint_limits return limits[0], limits[1] def get_home_position(robot: common.Robot) -> np.ndarray: """Returns the home position of the robot.""" - return common.robots_meta_config(robot.get_parameters().robot_type).q_home + return common.robots_meta_config(robot.get_config().robot_type).q_home class RobotEnv(gym.Env): diff --git a/src/pybind/rcs.cpp b/src/pybind/rcs.cpp index aa26abe7..e8f2521c 100644 --- a/src/pybind/rcs.cpp +++ b/src/pybind/rcs.cpp @@ -34,9 +34,9 @@ class PyRobot : public rcs::common::Robot { public: using rcs::common::Robot::Robot; // Inherit constructors - rcs::common::RobotConfig *get_parameters() override { + rcs::common::RobotConfig *get_config() override { PYBIND11_OVERRIDE_PURE(rcs::common::RobotConfig *, rcs::common::Robot, - get_parameters, ); + get_config, ); } rcs::common::RobotState *get_state() override { @@ -91,9 +91,9 @@ class PyGripper : public rcs::common::Gripper { public: using rcs::common::Gripper::Gripper; // Inherit constructors - rcs::common::GripperConfig *get_parameters() override { + rcs::common::GripperConfig *get_config() override { PYBIND11_OVERRIDE_PURE(rcs::common::GripperConfig *, rcs::common::Gripper, - get_parameters, ); + get_config, ); } rcs::common::GripperState *get_state() override { @@ -140,9 +140,9 @@ class PyHand : public rcs::common::Hand { public: using rcs::common::Hand::Hand; // Inherit constructors - rcs::common::HandConfig *get_parameters() override { + rcs::common::HandConfig *get_config() override { PYBIND11_OVERRIDE_PURE(rcs::common::HandConfig *, rcs::common::Hand, - get_parameters, ); + get_config, ); } rcs::common::HandState *get_state() override { @@ -355,7 +355,7 @@ PYBIND11_MODULE(_core, m) { py::class_>( common, "Robot") .def(py::init<>()) - .def("get_parameters", &rcs::common::Robot::get_parameters) + .def("get_config", &rcs::common::Robot::get_config) .def("get_state", &rcs::common::Robot::get_state) .def("get_cartesian_position", &rcs::common::Robot::get_cartesian_position) @@ -382,7 +382,7 @@ PYBIND11_MODULE(_core, m) { py::class_>(common, "Gripper") .def(py::init<>()) - .def("get_parameters", &rcs::common::Gripper::get_parameters) + .def("get_config", &rcs::common::Gripper::get_config) .def("get_state", &rcs::common::Gripper::get_state) .def("set_normalized_width", &rcs::common::Gripper::set_normalized_width, py::arg("width"), py::arg("force") = 0) @@ -402,7 +402,7 @@ PYBIND11_MODULE(_core, m) { py::class_>( common, "Hand") .def(py::init<>()) - .def("get_parameters", &rcs::common::Hand::get_parameters) + .def("get_config", &rcs::common::Hand::get_config) .def("get_state", &rcs::common::Hand::get_state) .def("set_normalized_joint_poses", &rcs::common::Hand::set_normalized_joint_poses, py::arg("q")) @@ -515,10 +515,9 @@ PYBIND11_MODULE(_core, m) { .def(py::init, const rcs::sim::SimGripperConfig &>(), py::arg("sim"), py::arg("cfg")) - .def("get_parameters", &rcs::sim::SimGripper::get_parameters) + .def("get_config", &rcs::sim::SimGripper::get_config) .def("get_state", &rcs::sim::SimGripper::get_state) - .def("set_parameters", &rcs::sim::SimGripper::set_parameters, - py::arg("cfg")); + .def("set_config", &rcs::sim::SimGripper::set_config, py::arg("cfg")); py::class_>(sim, "SimRobot") .def(py::init, @@ -526,9 +525,8 @@ PYBIND11_MODULE(_core, m) { bool>(), py::arg("sim"), py::arg("ik"), py::arg("cfg"), py::arg("register_convergence_callback") = true) - .def("get_parameters", &rcs::sim::SimRobot::get_parameters) - .def("set_parameters", &rcs::sim::SimRobot::set_parameters, - py::arg("cfg")) + .def("get_config", &rcs::sim::SimRobot::get_config) + .def("set_config", &rcs::sim::SimRobot::set_config, py::arg("cfg")) .def("set_joints_hard", &rcs::sim::SimRobot::set_joints_hard, py::arg("q")) .def("get_state", &rcs::sim::SimRobot::get_state); @@ -568,10 +566,9 @@ PYBIND11_MODULE(_core, m) { .def(py::init, const rcs::sim::SimTilburgHandConfig &>(), py::arg("sim"), py::arg("cfg")) - .def("get_parameters", &rcs::sim::SimTilburgHand::get_parameters) + .def("get_config", &rcs::sim::SimTilburgHand::get_config) .def("get_state", &rcs::sim::SimTilburgHand::get_state) - .def("set_parameters", &rcs::sim::SimTilburgHand::set_parameters, - py::arg("cfg")); + .def("set_config", &rcs::sim::SimTilburgHand::set_config, py::arg("cfg")); py::enum_(sim, "CameraType") .value("free", rcs::sim::CameraType::free) diff --git a/src/sim/SimGripper.cpp b/src/sim/SimGripper.cpp index f431e488..b2198ac9 100644 --- a/src/sim/SimGripper.cpp +++ b/src/sim/SimGripper.cpp @@ -57,14 +57,14 @@ void SimGripper::add_collision_geoms(const std::vector &cgeoms_str, } } -bool SimGripper::set_parameters(const SimGripperConfig &cfg) { +bool SimGripper::set_config(const SimGripperConfig &cfg) { this->cfg = cfg; this->add_collision_geoms(cfg.ignored_collision_geoms, this->ignored_collision_geoms, true); return true; } -SimGripperConfig *SimGripper::get_parameters() { +SimGripperConfig *SimGripper::get_config() { // copy config to heap SimGripperConfig *cfg = new SimGripperConfig(); *cfg = this->cfg; diff --git a/src/sim/SimGripper.h b/src/sim/SimGripper.h index 6d4cae79..6ff47002 100644 --- a/src/sim/SimGripper.h +++ b/src/sim/SimGripper.h @@ -71,9 +71,9 @@ class SimGripper : public common::Gripper { SimGripper(std::shared_ptr sim, const SimGripperConfig &cfg); ~SimGripper() override; - bool set_parameters(const SimGripperConfig &cfg); + bool set_config(const SimGripperConfig &cfg); - SimGripperConfig *get_parameters() override; + SimGripperConfig *get_config() override; SimGripperState *get_state() override; diff --git a/src/sim/SimRobot.cpp b/src/sim/SimRobot.cpp index cd13fe59..b94467d1 100644 --- a/src/sim/SimRobot.cpp +++ b/src/sim/SimRobot.cpp @@ -92,13 +92,13 @@ void SimRobot::init_ids() { } } -bool SimRobot::set_parameters(const SimRobotConfig& cfg) { +bool SimRobot::set_config(const SimRobotConfig& cfg) { this->cfg = cfg; this->state.inverse_tcp_offset = cfg.tcp_offset.inverse(); return true; } -SimRobotConfig* SimRobot::get_parameters() { +SimRobotConfig* SimRobot::get_config() { SimRobotConfig* cfg = new SimRobotConfig(); *cfg = this->cfg; return cfg; diff --git a/src/sim/SimRobot.h b/src/sim/SimRobot.h index 86724611..abfc0d2d 100644 --- a/src/sim/SimRobot.h +++ b/src/sim/SimRobot.h @@ -62,8 +62,8 @@ class SimRobot : public common::Robot { SimRobot(std::shared_ptr sim, std::shared_ptr ik, SimRobotConfig cfg, bool register_convergence_callback = true); ~SimRobot() override; - bool set_parameters(const SimRobotConfig &cfg); - SimRobotConfig *get_parameters() override; + bool set_config(const SimRobotConfig &cfg); + SimRobotConfig *get_config() override; SimRobotState *get_state() override; common::Pose get_cartesian_position() override; void set_joint_position(const common::VectorXd &q) override; diff --git a/src/sim/SimTilburgHand.cpp b/src/sim/SimTilburgHand.cpp index 45cc110c..ef407545 100644 --- a/src/sim/SimTilburgHand.cpp +++ b/src/sim/SimTilburgHand.cpp @@ -66,7 +66,7 @@ SimTilburgHand::~SimTilburgHand() {} // } // } -bool SimTilburgHand::set_parameters(const SimTilburgHandConfig &cfg) { +bool SimTilburgHand::set_config(const SimTilburgHandConfig &cfg) { auto current_grasp_type = this->cfg.grasp_type; this->cfg = cfg; if (!this->set_grasp_type(current_grasp_type)) { @@ -89,7 +89,7 @@ bool SimTilburgHand::set_grasp_type(common::GraspType grasp_type) { return true; } -SimTilburgHandConfig *SimTilburgHand::get_parameters() { +SimTilburgHandConfig *SimTilburgHand::get_config() { // copy config to heap SimTilburgHandConfig *cfg = new SimTilburgHandConfig(); *cfg = this->cfg; diff --git a/src/sim/SimTilburgHand.h b/src/sim/SimTilburgHand.h index 9ab36064..c100cde3 100644 --- a/src/sim/SimTilburgHand.h +++ b/src/sim/SimTilburgHand.h @@ -103,9 +103,9 @@ class SimTilburgHand : public common::Hand { SimTilburgHand(std::shared_ptr sim, const SimTilburgHandConfig &cfg); ~SimTilburgHand() override; - bool set_parameters(const SimTilburgHandConfig &cfg); + bool set_config(const SimTilburgHandConfig &cfg); - SimTilburgHandConfig *get_parameters() override; + SimTilburgHandConfig *get_config() override; SimTilburgHandState *get_state() override;