Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Jazzy Release #82

Open
gaspatxo opened this issue Jul 12, 2024 · 1 comment
Open

Jazzy Release #82

gaspatxo opened this issue Jul 12, 2024 · 1 comment

Comments

@gaspatxo
Copy link

Jazzy is an LTS version and sooner or later support for it should be developed

Moveit2 is not fully there yet due to the new gz_ros2_control packages; first that should be sorted out.

This also implies a transition from Gazebo Classic to Ignition Gazebo.

@nbubis
Copy link

nbubis commented Aug 3, 2024

To support jazzy, I had to modify some files and get rid of gazebo. Here's a patch for the modifications needed:

diff --git a/xarm_controller/src/hardware/uf_robot_system_hardware.cpp b/xarm_controller/src/hardware/uf_robot_system_hardware.cpp
index 79b45da..3001c3b 100644
--- a/xarm_controller/src/hardware/uf_robot_system_hardware.cpp
+++ b/xarm_controller/src/hardware/uf_robot_system_hardware.cpp
@@ -405,11 +405,11 @@ namespace uf_robot_hardware
     void UFRobotSystemHardware::_reload_controller(void) {
         int ret = _call_request(client_list_controller_, req_list_controller_, res_list_controller_);
         if (ret == 0 && res_list_controller_->controller.size() > 0) {
-            req_switch_controller_->start_controllers.resize(res_list_controller_->controller.size());
-            req_switch_controller_->stop_controllers.resize(res_list_controller_->controller.size());
+            req_switch_controller_->activate_controllers.resize(res_list_controller_->controller.size());
+            req_switch_controller_->deactivate_controllers.resize(res_list_controller_->controller.size());
             for (uint i = 0; i < res_list_controller_->controller.size(); i++) {
-                req_switch_controller_->start_controllers[i] = res_list_controller_->controller[i].name;
-                req_switch_controller_->stop_controllers[i] = res_list_controller_->controller[i].name;
+                req_switch_controller_->activate_controllers[i] = res_list_controller_->controller[i].name;
+                req_switch_controller_->deactivate_controllers[i] = res_list_controller_->controller[i].name;
             }
             req_switch_controller_->strictness = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
             _call_request(client_switch_controller_, req_switch_controller_, res_switch_controller_);
diff --git a/xarm_moveit_config/config/moveit_configs/ompl_planning.yaml b/xarm_moveit_config/config/moveit_configs/ompl_planning.yaml
index 99b4a9b..643beb2 100644
--- a/xarm_moveit_config/config/moveit_configs/ompl_planning.yaml
+++ b/xarm_moveit_config/config/moveit_configs/ompl_planning.yaml
@@ -1,10 +1,20 @@
-planning_plugin: ompl_interface/OMPLPlanner
+planning_plugin: [ompl_interface/OMPLPlanner]
 start_state_max_bounds_error: 0.1
 jiggle_fraction: 0.05
-request_adapters: >-
-    default_planner_request_adapters/AddTimeOptimalParameterization
-    default_planner_request_adapters/ResolveConstraintFrames
-    default_planner_request_adapters/FixWorkspaceBounds
-    default_planner_request_adapters/FixStartStateBounds
-    default_planner_request_adapters/FixStartStateCollision
-    default_planner_request_adapters/FixStartStatePathConstraints
\ No newline at end of file
+# request_adapters: >-
+#     default_planner_request_adapters/AddTimeOptimalParameterization
+#     default_planner_request_adapters/ResolveConstraintFrames
+#     default_planner_request_adapters/FixWorkspaceBounds
+#     default_planner_request_adapters/FixStartStateBounds
+#     default_planner_request_adapters/FixStartStateCollision
+#     default_planner_request_adapters/FixStartStatePathConstraints
+
+request_adapters:
+    - default_planning_request_adapters/ResolveConstraintFrames
+    - default_planning_request_adapters/ValidateWorkspaceBounds
+    - default_planning_request_adapters/CheckStartStateBounds
+    - default_planning_request_adapters/CheckStartStateCollision
+response_adapters:
+    - default_planning_response_adapters/AddTimeOptimalParameterization
+    - default_planning_response_adapters/ValidateSolution
+    - default_planning_response_adapters/DisplayMotionPath

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants