feat(rbs): refactor controller paths and launch configuration

- Rename default controllers file `rbs_arm0_controllers.yaml` to `controllers.yaml` across all launch files
- Enhance `runtime.launch.py` by adding imports (`URDF_parser`, `ControllerManager`, `yaml`) and new arguments (`scene_config_file`, `ee_link_name`, `base_link_name`)
  - Implement xacro argument loading via YAML
  - Configure `robot_builder` to save controllers to `controllers.yaml` based on URDF parsing
- Add `control.launch.py` in `rbs_bringup` for dynamic controller spawning based on strategies/configurations
- Add `rbs_bringup.launch.py` as a unified entry point for single robot setup, initializing core settings like gripper, robot type, and controllers
- Remove `launch_env.launch.py`
- Remove `multi_robot.launch.py`
- Enhance `rbs_robot.launch.py` with `ee_link_name` and `base_link_name` arguments for end-effector and base link customization
- Add `ee_link_name` and `base_link_name` to `skills.launch.py` for flexible robot setup in skills
- Update `mtp_jtc_cart.cpp` with `base_link` and `robot_ee_link` parameters for KDL chain retrieval
- Remove `single_robot.launch.py` for simplified single robot deployment
This commit is contained in:
Ilya Uraev 2024-11-12 22:23:12 +03:00
parent a7b7225dd1
commit ea4ae0ed69
13 changed files with 279 additions and 880 deletions

View file

@ -59,6 +59,8 @@ public:
std::placeholders::_1),
s_options);
this->declare_parameter("robot_description", "");
this->declare_parameter("base_link", "");
this->declare_parameter("robot_ee_link", "");
auto robot_description =
this->get_parameter("robot_description").as_string();
@ -70,7 +72,15 @@ public:
throw std::runtime_error("KDL Tree initialization failed");
}
if (!kdl_tree.getChain("base_link", "gripper_grasp_point", m_kdl_chain)) {
auto base_link = this->get_parameter("base_link").as_string();
auto robot_ee_link = this->get_parameter("robot_ee_link").as_string();
if (base_link.empty() or robot_ee_link.empty()) {
RCLCPP_ERROR(this->get_logger(),
"Describe robot end-effector link and base link to continue");
throw std::runtime_error("Describe robot end-effector link and base link to continue");
}
if (!kdl_tree.getChain(base_link, robot_ee_link, m_kdl_chain)) {
RCLCPP_ERROR(this->get_logger(),
"Failed to obtain KDL chain from base to end-effector.");
throw std::runtime_error("KDL Chain initialization failed");