MoveIt Resources for testing: Pilz PRBT 6
@@ -17,8 +17,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit-resources/issues
- https://github.com/ros-planning/moveit-resources
+ https://github.com/moveit/moveit-resources/issues
+ https://github.com/moveit/moveit-resources
ament_cmake
diff --git a/moveit_planners/test_configs/prbt_pg70_support/CHANGELOG.rst b/moveit_planners/test_configs/prbt_pg70_support/CHANGELOG.rst
index 2ef2500719..1084e487cf 100644
--- a/moveit_planners/test_configs/prbt_pg70_support/CHANGELOG.rst
+++ b/moveit_planners/test_configs/prbt_pg70_support/CHANGELOG.rst
@@ -2,6 +2,17 @@
Changelog for package moveit_resources_prbt_pg70_support
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Robert Haschke, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
diff --git a/moveit_planners/test_configs/prbt_pg70_support/package.xml b/moveit_planners/test_configs/prbt_pg70_support/package.xml
index 4bbdd0a22e..6f9e82aa2c 100644
--- a/moveit_planners/test_configs/prbt_pg70_support/package.xml
+++ b/moveit_planners/test_configs/prbt_pg70_support/package.xml
@@ -1,7 +1,7 @@
moveit_resources_prbt_pg70_support
- 2.9.0
+ 2.10.0
PRBT support for Schunk pg70 gripper.
Alexander Gutenkunst
@@ -11,8 +11,8 @@
Apache 2.0
http://moveit.ros.org
- https://github.com/ros-planning/moveit-resources/issues
- https://github.com/ros-planning/moveit-resources
+ https://github.com/moveit/moveit-resources/issues
+ https://github.com/moveit/moveit-resources
ament_cmake
diff --git a/moveit_planners/test_configs/prbt_support/CHANGELOG.rst b/moveit_planners/test_configs/prbt_support/CHANGELOG.rst
index 40a72cfa3a..92ee4c29fb 100644
--- a/moveit_planners/test_configs/prbt_support/CHANGELOG.rst
+++ b/moveit_planners/test_configs/prbt_support/CHANGELOG.rst
@@ -2,6 +2,17 @@
Changelog for package prbt_support
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Robert Haschke, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Update ros2_control usage (`#2620 `_)
diff --git a/moveit_planners/test_configs/prbt_support/package.xml b/moveit_planners/test_configs/prbt_support/package.xml
index e5d0a49d44..8cea882e64 100644
--- a/moveit_planners/test_configs/prbt_support/package.xml
+++ b/moveit_planners/test_configs/prbt_support/package.xml
@@ -1,6 +1,6 @@
moveit_resources_prbt_support
- 2.9.0
+ 2.10.0
Mechanical, kinematic and visual description
of the Pilz light weight arm PRBT.
@@ -12,8 +12,8 @@
Apache 2.0
http://moveit.ros.org
- https://github.com/ros-planning/moveit-resources/issues
- https://github.com/ros-planning/moveit-resources
+ https://github.com/moveit/moveit-resources/issues
+ https://github.com/moveit/moveit-resources
ament_cmake
diff --git a/moveit_plugins/moveit_plugins/CHANGELOG.rst b/moveit_plugins/moveit_plugins/CHANGELOG.rst
index fc665eda48..673ff39ab6 100644
--- a/moveit_plugins/moveit_plugins/CHANGELOG.rst
+++ b/moveit_plugins/moveit_plugins/CHANGELOG.rst
@@ -2,6 +2,11 @@
Changelog for package moveit_plugins
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
diff --git a/moveit_plugins/moveit_plugins/package.xml b/moveit_plugins/moveit_plugins/package.xml
index 0a766a856c..15027970ed 100644
--- a/moveit_plugins/moveit_plugins/package.xml
+++ b/moveit_plugins/moveit_plugins/package.xml
@@ -2,7 +2,7 @@
moveit_plugins
- 2.9.0
+ 2.10.0
Metapackage for MoveIt plugins.
Henning Kayser
diff --git a/moveit_plugins/moveit_ros_control_interface/CHANGELOG.rst b/moveit_plugins/moveit_ros_control_interface/CHANGELOG.rst
index ce620f18f7..db67aaada4 100644
--- a/moveit_plugins/moveit_ros_control_interface/CHANGELOG.rst
+++ b/moveit_plugins/moveit_ros_control_interface/CHANGELOG.rst
@@ -2,6 +2,20 @@
Changelog for package moveit_ros_control_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Revert "Simplify controller manager namespacing (`#2210 `_)"
+ This reverts commit 55df0bccd5e884649780b4ceeee80891e563b57b.
+ The deprecated constructor was being used in the same file
+ for the exact use case of enabling namespaces that are not
+ specified by the parameter. There is no replacement for
+ supporting a dynamic server lookup, however the parameter
+ logic could still use simplification.
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Henning Kayser, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Fix warning and cleanup unneeded placeholders (`#2566 `_)
diff --git a/moveit_plugins/moveit_ros_control_interface/package.xml b/moveit_plugins/moveit_ros_control_interface/package.xml
index 8f18410dce..e8a28c550f 100644
--- a/moveit_plugins/moveit_ros_control_interface/package.xml
+++ b/moveit_plugins/moveit_ros_control_interface/package.xml
@@ -2,7 +2,7 @@
moveit_ros_control_interface
- 2.9.0
+ 2.10.0
ros_control controller manager interface for MoveIt
Henning Kayser
Tyler Weaver
diff --git a/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp b/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp
index 89b5a7bb71..eb7b2e8205 100644
--- a/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp
+++ b/moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp
@@ -255,8 +255,7 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
* \brief Configure interface with namespace
* @param ns namespace of ros_control node (without /controller_manager/)
*/
- [[deprecated("Ros2ControlManager constructor with namespace is deprecated. Set namespace via the "
- "ros_control_namespace parameter.")]] Ros2ControlManager(const std::string& ns)
+ Ros2ControlManager(const std::string& ns)
: ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
{
RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
@@ -265,12 +264,18 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
void initialize(const rclcpp::Node::SharedPtr& node) override
{
node_ = node;
- // Set the namespace from the ros_control_namespace parameter, or default to "/"
- if (!node_->has_parameter("ros_control_namespace"))
+ if (!ns_.empty())
{
- ns_ = node_->declare_parameter("ros_control_namespace", "/");
+ if (!node_->has_parameter("ros_control_namespace"))
+ {
+ ns_ = node_->declare_parameter("ros_control_namespace", "/");
+ }
+ else
+ {
+ node_->get_parameter("ros_control_namespace", ns_);
+ }
}
- else
+ else if (node->has_parameter("ros_control_namespace"))
{
node_->get_parameter("ros_control_namespace", ns_);
RCLCPP_INFO_STREAM(getLogger(), "Namespace for controller manager was specified, namespace: " << ns_);
diff --git a/moveit_plugins/moveit_simple_controller_manager/CHANGELOG.rst b/moveit_plugins/moveit_simple_controller_manager/CHANGELOG.rst
index 5ab67379be..f94faab05e 100644
--- a/moveit_plugins/moveit_simple_controller_manager/CHANGELOG.rst
+++ b/moveit_plugins/moveit_simple_controller_manager/CHANGELOG.rst
@@ -2,6 +2,18 @@
Changelog for package moveit_simple_controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Unify log names (`#2720 `_)
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Robert Haschke, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Node logging for the rest of MoveIt (`#2599 `_)
diff --git a/moveit_plugins/moveit_simple_controller_manager/package.xml b/moveit_plugins/moveit_simple_controller_manager/package.xml
index e80e46f01c..d11a5cda19 100644
--- a/moveit_plugins/moveit_simple_controller_manager/package.xml
+++ b/moveit_plugins/moveit_simple_controller_manager/package.xml
@@ -2,7 +2,7 @@
moveit_simple_controller_manager
- 2.9.0
+ 2.10.0
A generic, simple controller manager plugin for MoveIt.
Michael Görner
Henning Kayser
@@ -12,8 +12,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Michael Ferguson
diff --git a/moveit_py/CHANGELOG.rst b/moveit_py/CHANGELOG.rst
index 6f6ba0fa95..00211b554f 100644
--- a/moveit_py/CHANGELOG.rst
+++ b/moveit_py/CHANGELOG.rst
@@ -2,6 +2,23 @@
Changelog for package moveit_py
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* Get configuration values of traj_exec_man (`#2702 `_)
+ * (ros_planning) get configuration values of traj_exec_man
+ * (py) get configuration values of traj_exec_man
+* CMake format and lint in pre-commit (`#2683 `_)
+* log after rclcpp init
+* Contributors: Henning Kayser, Matthijs van der Burgh, Robert Haschke, Sebastian Jahr, Tyler Weaver, peterdavidfagan
+
2.9.0 (2024-01-09)
------------------
* [PSM] Process collision object color when adding object trough the planning scene monitor (`#2567 `_)
diff --git a/moveit_py/CITATION.cff b/moveit_py/CITATION.cff
index ab0a59f44b..61e387555b 100644
--- a/moveit_py/CITATION.cff
+++ b/moveit_py/CITATION.cff
@@ -5,4 +5,4 @@ authors:
date-released: 2023-03-20
message: "If you use this software, please cite it as below."
title: "MoveIt 2 Python Library: A Software Library for Robotics Education and Research"
-url: "https://github.com/ros-planning/moveit2/tree/main/moveit_py"
+url: "https://github.com/moveit/moveit2/tree/main/moveit_py"
diff --git a/moveit_py/README.md b/moveit_py/README.md
index 8156807910..e903761ee5 100644
--- a/moveit_py/README.md
+++ b/moveit_py/README.md
@@ -26,7 +26,7 @@ If you use this library in your work please use the following citation:
@software{fagan2023moveitpy,
author = {Fagan, Peter David},
title = {{MoveIt 2 Python Library: A Software Library for Robotics Education and Research}},
- url = {https://github.com/ros-planning/moveit2/tree/main/moveit_py},
+ url = {https://github.com/moveit/moveit2/tree/main/moveit_py},
year = {2023}
}
```
diff --git a/moveit_py/package.xml b/moveit_py/package.xml
index f20bf5f2a5..cbc800cca0 100644
--- a/moveit_py/package.xml
+++ b/moveit_py/package.xml
@@ -2,7 +2,7 @@
moveit_py
- 2.9.0
+ 2.10.0
Python binding for MoveIt 2
Peter David Fagan
diff --git a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h
index e688705898..7ac1497b29 100644
--- a/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h
+++ b/moveit_py/src/moveit/moveit_core/robot_state/robot_state.h
@@ -38,7 +38,12 @@
#include
#include
+#pragma GCC diagnostic push
+#if defined(__GNUC__) && !defined(__clang__)
+#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
+#endif
#include
+#pragma GCC diagnostic pop
#include
#include
#include
diff --git a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp
index d4e7f7f901..3872d17665 100644
--- a/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp
+++ b/moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp
@@ -153,7 +153,7 @@ void initTrajectoryExecutionManager(py::module& m)
)")
// ToDo(MatthijsBurgh)
- // See https://github.com/ros-planning/moveit2/issues/2442
+ // See https://github.com/moveit/moveit2/issues/2442
// get_trajectories
.def("execute",
py::overload_cast`_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Fix CI for Rolling / Ubuntu Noble (`#2793 `_)
+ * docker.yaml: Enable caching
+ * [TEMP] moveit2_rolling.repos: add not yet released packages
+ * Skip broken ci-testing image: osrf/ros2:testing doesn't contain /opt/ros!
+ * use boost::timer::progress_display if available
+ check for header to stay compatible with ubuntu 20.04.
+ Support boost >= 1.83
+ Slightly ugly due to the double alias, but boost::timer was a class
+ before 1.72, so using `boost::timer::progress_display` in the code
+ breaks with older versions.
+ * cherry-pick of `#3547 `_ from MoveIt1
+ * Tag ci image as ci-testing as well
+ ---------
+ Co-authored-by: Michael Görner
+ Co-authored-by: Sebastian Jahr
+ Co-authored-by: Henning Kayser
+* Update deprecated include of boost/progress.hpp to boost/timer/progress_display.hpp (`#2811 `_)
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Robert Haschke, Sebastian Jahr, Stephanie Eng, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* [Planning Pipeline Refactoring] `#2 `_ Enable chaining planners (`#2457 `_)
diff --git a/moveit_ros/benchmarks/README.md b/moveit_ros/benchmarks/README.md
index 4823b68253..3201e2cf08 100644
--- a/moveit_ros/benchmarks/README.md
+++ b/moveit_ros/benchmarks/README.md
@@ -2,4 +2,4 @@
This package provides methods to benchmark motion planning algorithms and aggregate/plot statistics. Results can be viewed in [Planner Arena](http://plannerarena.org/).
-For more information and usage example please see [moveit tutorials](https://ros-planning.github.io/moveit_tutorials/doc/benchmarking/benchmarking_tutorial.html).
+For more information and usage example please see [moveit tutorials](https://moveit.github.io/moveit_tutorials/doc/benchmarking/benchmarking_tutorial.html).
diff --git a/moveit_ros/benchmarks/package.xml b/moveit_ros/benchmarks/package.xml
index 71c28e10b1..ce22554a6f 100644
--- a/moveit_ros/benchmarks/package.xml
+++ b/moveit_ros/benchmarks/package.xml
@@ -2,7 +2,7 @@
moveit_ros_benchmarks
- 2.9.0
+ 2.10.0
Enhanced tools for benchmarks in MoveIt
Henning Kayser
Tyler Weaver
@@ -11,8 +11,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Ryan Luna
diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
index 50760073fd..252d2a98d6 100644
--- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
+++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
@@ -43,10 +43,21 @@
#include
#include
-#define BOOST_ALLOW_DEPRECATED_HEADERS
#include
-#undef BOOST_ALLOW_DEPRECATED_HEADERS
+
+#if __has_include()
#include
+using boost_progress_display = boost::timer::progress_display;
+#else
+// boost < 1.72
+#define BOOST_TIMER_ENABLE_DEPRECATED 1
+#include
+#undef BOOST_TIMER_ENABLE_DEPRECATED
+using boost_progress_display = boost::progress_display;
+#endif
+
+#include
+#include
#include
#include
#include
@@ -773,7 +784,7 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::msg::MotionPlanRequest request
}
num_planners += options.parallel_planning_pipelines.size();
- boost::timer::progress_display progress(num_planners * options.runs, std::cout);
+ boost_progress_display progress(num_planners * options.runs, std::cout);
// Iterate through all planning pipelines
auto planning_pipelines = moveit_cpp_->getPlanningPipelines();
diff --git a/moveit_ros/hybrid_planning/CHANGELOG.rst b/moveit_ros/hybrid_planning/CHANGELOG.rst
index 8a85416307..291384011e 100644
--- a/moveit_ros/hybrid_planning/CHANGELOG.rst
+++ b/moveit_ros/hybrid_planning/CHANGELOG.rst
@@ -2,6 +2,21 @@
Changelog for package moveit_hybrid_planning
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Remove HP error codes interface (`#2774 `_)
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Clean-up hybrid planning package (`#2603 `_)
+* Contributors: Robert Haschke, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Update ros2_control usage (`#2620 `_)
diff --git a/moveit_ros/hybrid_planning/README.md b/moveit_ros/hybrid_planning/README.md
index defb1475c7..e31a4c5cee 100644
--- a/moveit_ros/hybrid_planning/README.md
+++ b/moveit_ros/hybrid_planning/README.md
@@ -1,5 +1,5 @@
# Hybrid Planning
-A Hybrid Planning architecture. You can find more information in the project's issues[#300](https://github.com/ros-planning/moveit2/issues/300), [#433](https://github.com/ros-planning/moveit2/issues/433) and on the [MoveIt 2 roadmap](https://moveit.ros.org/documentation/contributing/roadmap/). Furthermore, there is an extensive tutorial available [here](https://github.com/ros-planning/moveit2_tutorials/pull/97).
+A Hybrid Planning architecture. You can find more information in the project's issues[#300](https://github.com/moveit/moveit2/issues/300), [#433](https://github.com/moveit/moveit2/issues/433) and on the [MoveIt 2 roadmap](https://moveit.ros.org/documentation/contributing/roadmap/). Furthermore, there is an extensive tutorial available [here](https://github.com/moveit/moveit2_tutorials/pull/97).
## Getting started
To start the demo run:
diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp
index 77a0462045..ab4bb28c66 100644
--- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp
+++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp
@@ -318,7 +318,7 @@ void LocalPlannerComponent::executeIteration()
}
// Use a configurable message interface like MoveIt servo
- // (See https://github.com/ros-planning/moveit2/blob/main/moveit_ros/moveit_servo/src/servo_calcs.cpp)
+ // (See https://github.com/moveit/moveit2/blob/main/moveit_ros/moveit_servo/src/servo_calcs.cpp)
// Format outgoing msg in the right format
// (trajectory_msgs/JointTrajectory or joint positions/velocities in form of std_msgs/Float64MultiArray).
if (config_->local_solution_topic_type == "trajectory_msgs/JointTrajectory")
diff --git a/moveit_ros/hybrid_planning/package.xml b/moveit_ros/hybrid_planning/package.xml
index 5b96bca7f4..d61e4be425 100644
--- a/moveit_ros/hybrid_planning/package.xml
+++ b/moveit_ros/hybrid_planning/package.xml
@@ -1,6 +1,6 @@
moveit_hybrid_planning
- 2.9.0
+ 2.10.0
Hybrid planning components of MoveIt 2
Sebastian Jahr
@@ -9,8 +9,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
ament_cmake
moveit_common
diff --git a/moveit_ros/move_group/CHANGELOG.rst b/moveit_ros/move_group/CHANGELOG.rst
index 33222e381c..198f64aae0 100644
--- a/moveit_ros/move_group/CHANGELOG.rst
+++ b/moveit_ros/move_group/CHANGELOG.rst
@@ -2,6 +2,27 @@
Changelog for package moveit_ros_move_group
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* Remove extraneous error message from URDF service (`#2736 `_)
+* Add parameter api integration test (`#2662 `_)
+* CMake format and lint in pre-commit (`#2683 `_)
+* Get robot description from topic in GetUrdfService (`#2681 `_)
+* Fix bug in GetUrdfService move_group capability (`#2669 `_)
+ * Take both possible closings for links into account
+ * Make CI happy
+* avoid a relative jump threshold of 0.0 (`#2654 `_)
+* Add get group urdf capability (`#2649 `_)
+* Contributors: Abishalini Sivaraman, Ezra Brooks, Mario Prats, Robert Haschke, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Fix warning and cleanup unneeded placeholders (`#2566 `_)
diff --git a/moveit_ros/move_group/CMakeLists.txt b/moveit_ros/move_group/CMakeLists.txt
index 499c810176..6c4cdc9521 100644
--- a/moveit_ros/move_group/CMakeLists.txt
+++ b/moveit_ros/move_group/CMakeLists.txt
@@ -95,7 +95,7 @@ pluginlib_export_plugin_description_file(
if(BUILD_TESTING)
# TODO(henningkayser): enable rostests find_package(rostest REQUIRED) #
# rostest under development in ROS2
- # https://github.com/ros-planning/moveit2/issues/23 this test is flaky
+ # https://github.com/moveit/moveit2/issues/23 this test is flaky
# add_rostest(test/test_cancel_before_plan_execution.test)
# add_rostest(test/test_check_state_validity_in_empty_scene.test)
endif()
diff --git a/moveit_ros/move_group/package.xml b/moveit_ros/move_group/package.xml
index ccac01b94f..68cfb989ed 100644
--- a/moveit_ros/move_group/package.xml
+++ b/moveit_ros/move_group/package.xml
@@ -2,7 +2,7 @@
moveit_ros_move_group
- 2.9.0
+ 2.10.0
The move_group node for MoveIt
Michael Görner
Henning Kayser
@@ -12,8 +12,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Ioan Sucan
Sachin Chitta
diff --git a/moveit_ros/moveit_ros/CHANGELOG.rst b/moveit_ros/moveit_ros/CHANGELOG.rst
index ae0b079857..4df947049d 100644
--- a/moveit_ros/moveit_ros/CHANGELOG.rst
+++ b/moveit_ros/moveit_ros/CHANGELOG.rst
@@ -2,6 +2,17 @@
Changelog for package moveit_ros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Robert Haschke, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Merge branch 'main' into dependabot/github_actions/SonarSource/sonarcloud-github-c-cpp-2
diff --git a/moveit_ros/moveit_ros/package.xml b/moveit_ros/moveit_ros/package.xml
index 4f550e6f24..358f961e7d 100644
--- a/moveit_ros/moveit_ros/package.xml
+++ b/moveit_ros/moveit_ros/package.xml
@@ -2,7 +2,7 @@
moveit_ros
- 2.9.0
+ 2.10.0
Components of MoveIt that use ROS
Michael Görner
Henning Kayser
@@ -12,8 +12,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Ioan Sucan
Sachin Chitta
diff --git a/moveit_ros/moveit_servo/CHANGELOG.rst b/moveit_ros/moveit_servo/CHANGELOG.rst
index 191f8398c5..3a6ca13f28 100644
--- a/moveit_ros/moveit_servo/CHANGELOG.rst
+++ b/moveit_ros/moveit_servo/CHANGELOG.rst
@@ -2,6 +2,34 @@
Changelog for package moveit_servo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* remove intraprocess comm warning (`#2752 `_)
+* Fix error message text in servo.cpp (`#2769 `_)
+* Fix launch parameters in Servo demos (`#2735 `_)
+ Co-authored-by: Sebastian Jahr
+* [Servo] Fix collision checking with attached objects (`#2747 `_)
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Attempt to use SCHED_FIFO for Servo regardless of RT kernel (`#2653 `_)
+ * Attempt to use SCHED_FIFO for Servo regardless of RT kernel
+ * Update warning message if Servo fails to use SCHED_FIFO
+ Co-authored-by: AndyZe
+ * Update moveit_ros/moveit_servo/src/servo_node.cpp
+ Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
+ ---------
+ Co-authored-by: AndyZe
+ Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
+* Acceleration Limited Smoothing Plugin for Servo (`#2651 `_)
+* Contributors: Marc Bestmann, Nathan Brooks, Paul Gesel, Robert Haschke, Sebastian Castro, Sebastian Jahr, Stephanie Eng, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Add command queue to servo to account for latency (`#2594 `_)
diff --git a/moveit_ros/moveit_servo/config/panda_simulated_config.yaml b/moveit_ros/moveit_servo/config/panda_simulated_config.yaml
index ac3d0eb068..b5d57bfcb9 100644
--- a/moveit_ros/moveit_servo/config/panda_simulated_config.yaml
+++ b/moveit_ros/moveit_servo/config/panda_simulated_config.yaml
@@ -44,7 +44,7 @@ move_group_name: panda_arm # Often 'manipulator' or 'arm'
lower_singularity_threshold: 17.0 # Start decelerating when the condition number hits this (close to singularity)
hard_stop_singularity_threshold: 30.0 # Stop when the condition number hits this
joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians or meters]. If moving quickly, make this larger.
-leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/ros-planning/moveit2/pull/620)
+leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/moveit/moveit2/pull/620)
## Topic names
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands
diff --git a/moveit_ros/moveit_servo/config/test_config_panda.yaml b/moveit_ros/moveit_servo/config/test_config_panda.yaml
index 0698fd846a..5324ce9bf1 100644
--- a/moveit_ros/moveit_servo/config/test_config_panda.yaml
+++ b/moveit_ros/moveit_servo/config/test_config_panda.yaml
@@ -43,7 +43,7 @@ move_group_name: panda_arm # Often 'manipulator' or 'arm'
lower_singularity_threshold: 17.0 # Start decelerating when the condition number hits this (close to singularity)
hard_stop_singularity_threshold: 30.0 # Stop when the condition number hits this
joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians or meters]. If moving quickly, make this larger.
-leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/ros-planning/moveit2/pull/620)
+leaving_singularity_threshold_multiplier: 2.0 # Multiply the hard stop limit by this when leaving singularity (see https://github.com/moveit/moveit2/pull/620)
## Topic names
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands
diff --git a/moveit_ros/moveit_servo/package.xml b/moveit_ros/moveit_servo/package.xml
index edfc14d0d6..574d89dad8 100644
--- a/moveit_ros/moveit_servo/package.xml
+++ b/moveit_ros/moveit_servo/package.xml
@@ -2,7 +2,7 @@
moveit_servo
- 2.9.0
+ 2.10.0
Provides real-time manipulator Cartesian and joint servoing.
Blake Anderson
Andy Zelenak
@@ -11,7 +11,7 @@
BSD-3-Clause
- https://ros-planning.github.io/moveit_tutorials
+ https://moveit.github.io/moveit_tutorials
Brian O'Neil
Andy Zelenak
diff --git a/moveit_ros/moveit_servo/src/collision_monitor.cpp b/moveit_ros/moveit_servo/src/collision_monitor.cpp
index 719d0112ec..c3a886cff8 100644
--- a/moveit_ros/moveit_servo/src/collision_monitor.cpp
+++ b/moveit_ros/moveit_servo/src/collision_monitor.cpp
@@ -106,7 +106,7 @@ void CollisionMonitor::checkCollisions()
if (servo_params_.check_collisions)
{
// Fetch latest robot state using planning scene instead of state monitor due to
- // https://github.com/ros-planning/moveit2/issues/2748
+ // https://github.com/moveit/moveit2/issues/2748
robot_state_ = planning_scene_monitor_->getPlanningScene()->getCurrentState();
// This must be called before doing collision checking.
robot_state_.updateCollisionBodyTransforms();
diff --git a/moveit_ros/moveit_servo/src/utils/common.cpp b/moveit_ros/moveit_servo/src/utils/common.cpp
index ea1512984e..66b0866819 100644
--- a/moveit_ros/moveit_servo/src/utils/common.cpp
+++ b/moveit_ros/moveit_servo/src/utils/common.cpp
@@ -343,7 +343,7 @@ std::pair velocityScalingFactorForSingularity(const moveit::
const bool moving_towards_singularity = vector_towards_singularity.dot(target_delta_x) > 0;
// Compute upper condition variable threshold based on if we are moving towards or away from singularity.
- // See https://github.com/ros-planning/moveit2/pull/620#issuecomment-1201418258 for visual explanation.
+ // See https://github.com/moveit/moveit2/pull/620#issuecomment-1201418258 for visual explanation.
double upper_threshold;
if (moving_towards_singularity)
{
diff --git a/moveit_ros/occupancy_map_monitor/CHANGELOG.rst b/moveit_ros/occupancy_map_monitor/CHANGELOG.rst
index fb88df21b6..98b1330284 100644
--- a/moveit_ros/occupancy_map_monitor/CHANGELOG.rst
+++ b/moveit_ros/occupancy_map_monitor/CHANGELOG.rst
@@ -2,6 +2,20 @@
Changelog for package moveit_ros_occupancy_map_monitor
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Enforce liboctomap-dev by using a cmake version range
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: Henning Kayser, Robert Haschke, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* Node logging in moveit_core (`#2503 `_)
diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt
index f10094d162..b8dd549bcb 100644
--- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt
+++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt
@@ -13,7 +13,9 @@ find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(Eigen3 REQUIRED)
-find_package(octomap REQUIRED)
+# Enforce system version liboctomap-dev
+# https://github.com/moveit/moveit2/issues/2862
+find_package(octomap 1.9.7...<1.10.0 REQUIRED)
find_package(geometric_shapes REQUIRED)
find_package(tf2_ros REQUIRED)
diff --git a/moveit_ros/occupancy_map_monitor/package.xml b/moveit_ros/occupancy_map_monitor/package.xml
index d82f4d5e9c..6ba31b2f19 100644
--- a/moveit_ros/occupancy_map_monitor/package.xml
+++ b/moveit_ros/occupancy_map_monitor/package.xml
@@ -2,7 +2,7 @@
moveit_ros_occupancy_map_monitor
- 2.9.0
+ 2.10.0
Components of MoveIt connecting to occupancy map
Henning Kayser
Tyler Weaver
@@ -11,8 +11,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Ioan Sucan
Jon Binney
@@ -26,7 +26,13 @@
rclcpp
moveit_core
moveit_msgs
+
pluginlib
tf2_ros
geometric_shapes
diff --git a/moveit_ros/perception/CHANGELOG.rst b/moveit_ros/perception/CHANGELOG.rst
index e058f161d3..e347a0bdcd 100644
--- a/moveit_ros/perception/CHANGELOG.rst
+++ b/moveit_ros/perception/CHANGELOG.rst
@@ -2,6 +2,20 @@
Changelog for package moveit_ros_perception
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Fix segmentation fault in mesh_filter/gl_renderer (`#2834 `_)
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* CMake format and lint in pre-commit (`#2683 `_)
+* Contributors: CihatAltiparmak, Robert Haschke, Sebastian Jahr, Tyler Weaver
+
2.9.0 (2024-01-09)
------------------
* (moveit_ros) add missing CYLINDER check (`#2640 `_)
diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
index 000dc7ff7b..3c2d7d29e3 100644
--- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
+++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp
@@ -387,7 +387,7 @@ void mesh_filter::GLRenderer::createGLContext()
if (context_it == s_context.end())
{
- s_context.at(thread_id) = std::pair(1, 0);
+ s_context.insert({ thread_id, std::pair(1, 0) });
glutInitWindowPosition(glutGet(GLUT_SCREEN_WIDTH) + 30000, 0);
glutInitWindowSize(1, 1);
diff --git a/moveit_ros/perception/package.xml b/moveit_ros/perception/package.xml
index 8b55305797..a50c122553 100644
--- a/moveit_ros/perception/package.xml
+++ b/moveit_ros/perception/package.xml
@@ -2,7 +2,7 @@
moveit_ros_perception
- 2.9.0
+ 2.10.0
Components of MoveIt connecting to perception
Henning Kayser
Tyler Weaver
@@ -11,8 +11,8 @@
BSD-3-Clause
http://moveit.ros.org
- https://github.com/ros-planning/moveit2/issues
- https://github.com/ros-planning/moveit2
+ https://github.com/moveit/moveit2/issues
+ https://github.com/moveit/moveit2
Ioan Sucan
Jon Binney
diff --git a/moveit_ros/planning/CHANGELOG.rst b/moveit_ros/planning/CHANGELOG.rst
index e4d9da718e..b8b17e2d80 100644
--- a/moveit_ros/planning/CHANGELOG.rst
+++ b/moveit_ros/planning/CHANGELOG.rst
@@ -2,6 +2,74 @@
Changelog for package moveit_ros_planning
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.10.0 (2024-06-13)
+-------------------
+* Apply clang-tidy fixes
+* Migrate ros-planning org to moveit (`#2847 `_)
+ * Rename github.com/ros-planning -> github.com/moveit
+ * Rename ros-planning.github.io -> moveit.github.io
+ * Rename ros-planning organization in docker and CI workflow files
+ - ghcr.io/ros-planning -> ghcr.io/moveit
+ - github.repository == 'moveit/*''
+* Enable mdof trajectory execution (`#2740 `_)
+ * Add RobotTrajectory conversion from MDOF to joints
+ * Convert MDOF trajectories to joint trajectories in planning interfaces
+ * Treat mdof joint variables as common joints in
+ TrajectoryExecutionManager
+ * Convert multi-DOF trajectories to joints in TEM
+ * Revert "Convert MDOF trajectories to joint trajectories in planning interfaces"
+ This reverts commit 885ee2718594859555b73dc341311a859d31216e.
+ * Handle multi-DOF variables in TEM's bound checking
+ * Add parameter to optionally enable multi-dof conversion
+ * Improve error message about unknown controllers
+ * Fix name ordering in JointTrajectory conversion
+ * Improve DEBUG output in TEM
+ * Comment RobotTrajectory test
+ * add acceleration to avoid out of bounds read
+ ---------
+ Co-authored-by: Paul Gesel
+ Co-authored-by: Abishalini Sivaraman
+ Co-authored-by: Ezra Brooks
+* Skip flaky PSM launch test (`#2822 `_)
+* change default to 1e308 (`#2801 `_)
+* PSM: keep references to scene\_ valid upon receiving full scenes (`#2745 `_)
+ plan_execution-related modules rely on `plan.planning_scene\_` in many places
+ to point to the currently monitored scene (or a diff on top of it).
+ Before this patch, if the PSM would receive full scenes during execution,
+ `plan.planning_scene\_` would not include later incremental updates anymore
+ because the monitor created a new diff scene.
+ ---------
+ Co-authored-by: v4hn
+* Unify log names (`#2720 `_)
+ Co-authored-by: Abishalini Sivaraman
+* Print links in collision (`#2727 `_)
+* Do not overwrite the error code in planWithSinglePipeline (`#2723 `_)
+ * Do not overwrite the error code in planWithSinglePipeline
+ Return the `MotionPlanResponse` as-is.
+ * Do not rely on generatePlan() to set error code
+ Do not rely on generatePlan() to set the error code in all cases and
+ ensure that the error code is set to FAILURE if `generatePlan()` returns
+ false.
+ ---------
+ Co-authored-by: Gaël Écorchard
+* Get configuration values of traj_exec_man (`#2702 `_)
+ * (ros_planning) get configuration values of traj_exec_man
+ * (py) get configuration values of traj_exec_man
+ ---------
+ Co-authored-by: Sebastian Jahr
+* Exit earlier on failure in `generatePlan` (`#2726 `_)
+ With this change, the `PlanningPipeline::generatePlan()` exits as soon
+ as a failure is detected. Before this, `break` was used to exit the
+ current loop of request adapters, planners, or response adapters, but
+ the function continued to the next loop. For example, if a planner would
+ fail, the response adapters would still be executed.
+ Co-authored-by: Gaël Écorchard
+* srdf publisher node (`#2682 `_)
+* CMake format and lint in pre-commit (`#2683