Skip to content

Commit ac1e808

Browse files
authored
Merge branch 'moveit:main' into patch-3
2 parents 9beb253 + 660175c commit ac1e808

File tree

180 files changed

+1973
-798
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

180 files changed

+1973
-798
lines changed

.github/workflows/ci.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ jobs:
3939
moveit2.repos
4040
$(f="moveit2_$(sed 's/-.*$//' <<< "${{ matrix.env.IMAGE }}").repos"; test -r $f && echo $f)
4141
# Pull any updates to the upstream workspace (after restoring it from cache)
42-
AFTER_SETUP_UPSTREAM_WORKSPACE: apt remove -y ros-$ROS_DISTRO-geometric-shapes; vcs pull $BASEDIR/upstream_ws/src
42+
AFTER_SETUP_UPSTREAM_WORKSPACE: vcs pull $BASEDIR/upstream_ws/src
4343
AFTER_SETUP_DOWNSTREAM_WORKSPACE: vcs pull $BASEDIR/downstream_ws/src
4444
# Clear the ccache stats before and log the stats after the build
4545
AFTER_SETUP_CCACHE: ccache --zero-stats --max-size=10.0G
@@ -157,6 +157,7 @@ jobs:
157157
with:
158158
name: test-results-${{ matrix.env.IMAGE }}
159159
path: ${{ env.BASEDIR }}/target_ws/**/test_results/**/*.xml
160+
overwrite: true
160161
- name: Generate codecov report
161162
uses: rhaschke/lcov-action@main
162163
if: always() && matrix.env.CCOV && steps.ici.outputs.target_test_results == '0'

README.md

+48-41
Large diffs are not rendered by default.

moveit/CHANGELOG.rst

+3
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
Changelog for package moveit
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.13.0 (2025-02-15)
6+
-------------------
7+
58
2.12.0 (2024-11-29)
69
-------------------
710
* Enhancement/use hpp for headers (`#3113 <https://github.com/ros-planning/moveit2/issues/3113>`_)

moveit/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>moveit</name>
5-
<version>2.12.0</version>
5+
<version>2.13.0</version>
66
<description>Meta package that contains all essential packages of MoveIt 2</description>
77
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
88
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>

moveit2.repos

-8
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,5 @@
11
repositories:
22
# Keep moveit_* repos here because they are released with moveit
3-
geometric_shapes:
4-
type: git
5-
url: https://github.com/moveit/geometric_shapes.git
6-
version: ros2
73
moveit_msgs:
84
type: git
95
url: https://github.com/moveit/moveit_msgs.git
@@ -12,7 +8,3 @@ repositories:
128
type: git
139
url: https://github.com/moveit/moveit_resources.git
1410
version: ros2
15-
srdfdom:
16-
type: git
17-
url: https://github.com/moveit/srdfdom.git
18-
version: ros2

moveit_common/CHANGELOG.rst

+3
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
Changelog for package moveit_common
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.13.0 (2025-02-15)
6+
-------------------
7+
58
2.12.0 (2024-11-29)
69
-------------------
710

moveit_common/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>moveit_common</name>
5-
<version>2.12.0</version>
5+
<version>2.13.0</version>
66
<description>Common support functionality used throughout MoveIt</description>
77
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>
88
<maintainer email="tyler@picknik.ai">Tyler Weaver</maintainer>

moveit_configs_utils/CHANGELOG.rst

+3
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
Changelog for package moveit_configs_utils
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.13.0 (2025-02-15)
6+
-------------------
7+
58
2.12.0 (2024-11-29)
69
-------------------
710
* Added joint limits to rviz launch file. (`#3091 <https://github.com/ros-planning/moveit2/issues/3091>`_)

moveit_configs_utils/default_configs/ompl_defaults.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
planner_configs:
22
AnytimePathShortening:
33
type: geometric::AnytimePathShortening
4-
shortcut: true # Attempt to shortcut all new solution paths
5-
hybridize: true # Compute hybrid solution trajectories
4+
shortcut: 1 # Attempt to shortcut all new solution paths
5+
hybridize: 1 # Compute hybrid solution trajectories
66
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
77
num_planners: 4 # The number of default planners to use for planning
88
planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"

moveit_configs_utils/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>moveit_configs_utils</name>
5-
<version>2.12.0</version>
5+
<version>2.13.0</version>
66
<description>Python library for loading moveit config parameters in launch files</description>
77
<maintainer email="moveit_releasers@googlegroups.com">MoveIt Release Team</maintainer>
88
<license>BSD-3-Clause</license>

moveit_configs_utils/setup.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55

66
setup(
77
name=package_name,
8-
version="2.12.0",
8+
version="2.13.0",
99
packages=find_packages(),
1010
data_files=[
1111
("share/ament_index/resource_index/packages", ["resource/" + package_name]),

moveit_core/CHANGELOG.rst

+15
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,21 @@
22
Changelog for package moveit_core
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.13.0 (2025-02-15)
6+
-------------------
7+
* Reverts `#2985 <https://github.com/ros-planning/moveit2/issues/2985>`_, Ports moveit `#3388 <https://github.com/ros-planning/moveit2/issues/3388>`_ `#3470 <https://github.com/ros-planning/moveit2/issues/3470>`_ `#3539 <https://github.com/ros-planning/moveit2/issues/3539>`_ (`#3284 <https://github.com/ros-planning/moveit2/issues/3284>`_)
8+
* Add missing target dependencies to eigen_stl_containers (`#3295 <https://github.com/ros-planning/moveit2/issues/3295>`_)
9+
* Support including the names of other attached objects in `touch_link` (`#3276 <https://github.com/ros-planning/moveit2/issues/3276>`_)
10+
* Fix: misleading error logs in RobotState::setFromIKSubgroups() (`#3263 <https://github.com/ros-planning/moveit2/issues/3263>`_)
11+
* Update includes for generate_parameter_library 0.4.0 (`#3255 <https://github.com/ros-planning/moveit2/issues/3255>`_)
12+
* Remove plugins from export set (`#3227 <https://github.com/ros-planning/moveit2/issues/3227>`_)
13+
* [Issue-879] Add const specifier to moveit_core (`#3202 <https://github.com/ros-planning/moveit2/issues/3202>`_)
14+
* Don't destroy objects on attach (`#3205 <https://github.com/ros-planning/moveit2/issues/3205>`_)
15+
* Update deprecated tf2 imports from .h to .hpp (`#3197 <https://github.com/ros-planning/moveit2/issues/3197>`_)
16+
* Remove ACM entries when removing collision objects (`#3183 <https://github.com/ros-planning/moveit2/issues/3183>`_)
17+
* handle continuous joints in getLowerAndUpperLimits (`#3153 <https://github.com/ros-planning/moveit2/issues/3153>`_)
18+
* Contributors: Aleksey Nogin, Jafar Uruç, Mario Prats, Mark Johnson, Marq Rasmussen, Michael Görner, Paul Gesel, Sebastian Castro, Robert Haschke, Zhong Jin, gayar
19+
520
2.12.0 (2024-11-29)
621
-------------------
722
* Enhancement/use hpp for headers (`#3113 <https://github.com/ros-planning/moveit2/issues/3113>`_)

moveit_core/CMakeLists.txt

+15-9
Original file line numberDiff line numberDiff line change
@@ -69,13 +69,7 @@ add_subdirectory(utils)
6969
add_subdirectory(version)
7070

7171
install(
72-
TARGETS collision_detector_bullet_plugin
73-
collision_detector_fcl_plugin
74-
moveit_acceleration_filter
75-
moveit_acceleration_filter_parameters
76-
moveit_butterworth_filter
77-
moveit_butterworth_filter_parameters
78-
moveit_collision_detection
72+
TARGETS moveit_collision_detection
7973
moveit_collision_detection_bullet
8074
moveit_collision_detection_fcl
8175
moveit_collision_distance_field
@@ -92,8 +86,6 @@ install(
9286
moveit_robot_model
9387
moveit_robot_state
9488
moveit_robot_trajectory
95-
moveit_ruckig_filter
96-
moveit_ruckig_filter_parameters
9789
moveit_smoothing_base
9890
moveit_test_utils
9991
moveit_trajectory_processing
@@ -104,6 +96,20 @@ install(
10496
ARCHIVE DESTINATION lib
10597
RUNTIME DESTINATION bin)
10698

99+
install(
100+
TARGETS collision_detector_bullet_plugin
101+
collision_detector_fcl_plugin
102+
moveit_acceleration_filter
103+
moveit_acceleration_filter_parameters
104+
moveit_butterworth_filter
105+
moveit_butterworth_filter_parameters
106+
moveit_ruckig_filter
107+
moveit_ruckig_filter_parameters
108+
EXPORT moveit_core_pluginTargets
109+
LIBRARY DESTINATION lib
110+
ARCHIVE DESTINATION lib
111+
RUNTIME DESTINATION bin)
112+
107113
ament_export_targets(moveit_coreTargets HAS_LIBRARY_TARGET)
108114
ament_export_dependencies(
109115
angles

moveit_core/collision_detection/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ generate_export_header(moveit_collision_detection)
1818

1919
ament_target_dependencies(
2020
moveit_collision_detection
21+
eigen_stl_containers
2122
pluginlib
2223
rclcpp
2324
rmw_implementation

moveit_core/collision_detection_fcl/src/collision_common.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -155,11 +155,30 @@ bool collisionCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, voi
155155
}
156156
}
157157
}
158+
158159
// bodies attached to the same link should not collide
160+
// If one of the attached objects lists the other in touch links set, then collisions are also allowed
159161
if (cd1->type == BodyTypes::ROBOT_ATTACHED && cd2->type == BodyTypes::ROBOT_ATTACHED)
160162
{
161163
if (cd1->ptr.ab->getAttachedLink() == cd2->ptr.ab->getAttachedLink())
164+
{
162165
always_allow_collision = true;
166+
}
167+
else
168+
{
169+
const std::set<std::string>& tl1 = cd1->ptr.ab->getTouchLinks();
170+
const std::set<std::string>& tl2 = cd2->ptr.ab->getTouchLinks();
171+
if (tl1.find(cd2->getID()) != tl1.end() || tl2.find(cd1->getID()) != tl2.end())
172+
{
173+
always_allow_collision = true;
174+
}
175+
}
176+
if (always_allow_collision && cdata->req_->verbose)
177+
{
178+
RCLCPP_DEBUG(getLogger(),
179+
"Attached object '%s' is allowed to touch attached object '%s'. No contacts are computed.",
180+
cd2->getID().c_str(), cd1->getID().c_str());
181+
}
163182
}
164183

165184
// if collisions are always allowed, we are done

moveit_core/distance_field/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ set_target_properties(moveit_distance_field
1212
ament_target_dependencies(
1313
moveit_distance_field
1414
Boost
15+
eigen_stl_containers
1516
urdfdom
1617
urdfdom_headers
1718
visualization_msgs

moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/acceleration_filter.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ c --------x--- v |
7878
#include <moveit/robot_model/robot_model.hpp>
7979
#include <moveit/robot_state/robot_state.hpp>
8080
#include <moveit/utils/logger.hpp>
81-
#include <moveit_acceleration_filter_parameters.hpp>
81+
#include <moveit_core/moveit_acceleration_filter_parameters.hpp>
8282

8383
#include <osqp.h>
8484
#include <types.h>

moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/butterworth_filter.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,9 +41,9 @@
4141

4242
#include <cstddef>
4343

44-
#include <moveit_butterworth_filter_parameters.hpp>
4544
#include <moveit/robot_model/robot_model.hpp>
4645
#include <moveit/online_signal_smoothing/smoothing_base_class.hpp>
46+
#include <moveit_core/moveit_butterworth_filter_parameters.hpp>
4747

4848
namespace online_signal_smoothing
4949
{

moveit_core/online_signal_smoothing/include/moveit/online_signal_smoothing/ruckig_filter.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ Description: Applies jerk/acceleration/velocity limits to online motion commands
4242

4343
#include <moveit/robot_model/robot_model.hpp>
4444
#include <moveit/online_signal_smoothing/smoothing_base_class.hpp>
45-
#include <moveit_ruckig_filter_parameters.hpp>
45+
#include <moveit_core/moveit_ruckig_filter_parameters.hpp>
4646

4747
#include <ruckig/ruckig.hpp>
4848

moveit_core/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>moveit_core</name>
5-
<version>2.12.0</version>
5+
<version>2.13.0</version>
66
<description>Core libraries used by MoveIt</description>
77

88
<maintainer email="henningkayser@picknik.ai">Henning Kayser</maintainer>

moveit_core/robot_model/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ ament_target_dependencies(
3333
angles
3434
moveit_msgs
3535
Eigen3
36+
eigen_stl_containers
3637
geometric_shapes
3738
urdf
3839
urdfdom_headers

moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -255,6 +255,9 @@ class RobotModel
255255
LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr);
256256

257257
/** \brief Get the latest link upwards the kinematic tree, which is only connected via fixed joints
258+
*
259+
* If jmg is given, all links that are not active in this JMG are considered fixed.
260+
* Otherwise only fixed joints are considered fixed.
258261
*
259262
* This is useful, if the link should be warped to a specific pose using updateStateWithLinkAt().
260263
* As updateStateWithLinkAt() warps only the specified link and its descendants, you might not
@@ -265,7 +268,8 @@ class RobotModel
265268
* what you went for. Instead, updateStateWithLinkAt(getRigidlyConnectedParentLinkModel(grasp_frame), ...)
266269
* will actually warp wrist (and all its descendants).
267270
*/
268-
static const moveit::core::LinkModel* getRigidlyConnectedParentLinkModel(const LinkModel* link);
271+
static const LinkModel* getRigidlyConnectedParentLinkModel(const LinkModel* link,
272+
const JointModelGroup* jmg = nullptr);
269273

270274
/** \brief Get the array of links */
271275
const std::vector<const LinkModel*>& getLinkModels() const

moveit_core/robot_model/src/robot_model.cpp

+20-2
Original file line numberDiff line numberDiff line change
@@ -1364,14 +1364,32 @@ LinkModel* RobotModel::getLinkModel(const std::string& name, bool* has_link)
13641364
return nullptr;
13651365
}
13661366

1367-
const LinkModel* RobotModel::getRigidlyConnectedParentLinkModel(const LinkModel* link)
1367+
const LinkModel* RobotModel::getRigidlyConnectedParentLinkModel(const LinkModel* link, const JointModelGroup* jmg)
13681368
{
13691369
if (!link)
13701370
return link;
1371+
13711372
const moveit::core::LinkModel* parent_link = link->getParentLinkModel();
13721373
const moveit::core::JointModel* joint = link->getParentJointModel();
1374+
decltype(jmg->getJointModels().cbegin()) begin{}, end{};
1375+
if (jmg)
1376+
{
1377+
begin = jmg->getJointModels().cbegin();
1378+
end = jmg->getJointModels().cend();
1379+
}
1380+
1381+
// Returns whether `joint` is part of the rigidly connected chain.
1382+
// This is only false if the joint is both in `jmg` and not fixed.
1383+
auto is_fixed_or_not_in_jmg = [begin, end](const JointModel* joint) {
1384+
if (joint->getType() == JointModel::FIXED)
1385+
return true;
1386+
if (begin != end && // we do have a non-empty jmg
1387+
std::find(begin, end, joint) == end) // joint does not belong to jmg
1388+
return true;
1389+
return false;
1390+
};
13731391

1374-
while (parent_link && joint->getType() == moveit::core::JointModel::FIXED)
1392+
while (parent_link && is_fixed_or_not_in_jmg(joint))
13751393
{
13761394
link = parent_link;
13771395
joint = link->getParentJointModel();

moveit_core/robot_state/CMakeLists.txt

+9-3
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,14 @@ target_include_directories(
77
$<INSTALL_INTERFACE:include/moveit_core>)
88
set_target_properties(moveit_robot_state PROPERTIES VERSION
99
${${PROJECT_NAME}_VERSION})
10-
ament_target_dependencies(moveit_robot_state urdf tf2_geometry_msgs
11-
geometric_shapes urdfdom_headers Boost)
10+
ament_target_dependencies(
11+
moveit_robot_state
12+
eigen_stl_containers
13+
urdf
14+
tf2_geometry_msgs
15+
geometric_shapes
16+
urdfdom_headers
17+
Boost)
1218
target_link_libraries(moveit_robot_state moveit_robot_model
1319
moveit_kinematics_base moveit_transforms)
1420

@@ -31,7 +37,7 @@ if(BUILD_TESTING)
3137
"${CMAKE_CURRENT_BINARY_DIR};${CMAKE_CURRENT_BINARY_DIR}/../utils")
3238
endif()
3339

34-
ament_add_gtest(test_robot_state test/robot_state_test.cpp
40+
ament_add_gmock(test_robot_state test/robot_state_test.cpp
3541
APPEND_LIBRARY_DIRS "${APPEND_LIBRARY_DIRS}")
3642

3743
target_link_libraries(test_robot_state moveit_test_utils moveit_utils

moveit_core/robot_state/include/moveit/robot_state/attached_body.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -167,13 +167,6 @@ class AttachedBody
167167
* The returned transform is guaranteed to be a valid isometry. */
168168
const Eigen::Isometry3d& getSubframeTransform(const std::string& frame_name, bool* found = nullptr) const;
169169

170-
/** \brief Get the fixed transform to a named subframe on this body (relative to the robot link)
171-
*
172-
* The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's
173-
* name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false).
174-
* The returned transform is guaranteed to be a valid isometry. */
175-
const Eigen::Isometry3d& getSubframeTransformInLinkFrame(const std::string& frame_name, bool* found = nullptr) const;
176-
177170
/** \brief Get the fixed transform to a named subframe on this body, relative to the world frame.
178171
* The frame_name needs to have the object's name prepended (e.g. "screwdriver/tip" returns true if the object's
179172
* name is "screwdriver"). Returns an identity transform if frame_name is unknown (and set found to false).

moveit_core/robot_state/include/moveit/robot_state/robot_state.hpp

+9-1
Original file line numberDiff line numberDiff line change
@@ -1231,7 +1231,8 @@ class RobotState
12311231
* This behaves the same as RobotModel::getRigidlyConnectedParentLinkModel,
12321232
* but can additionally resolve parents for attached objects / subframes.
12331233
*/
1234-
const moveit::core::LinkModel* getRigidlyConnectedParentLinkModel(const std::string& frame) const;
1234+
const moveit::core::LinkModel*
1235+
getRigidlyConnectedParentLinkModel(const std::string& frame, const moveit::core::JointModelGroup* jmg = nullptr) const;
12351236

12361237
/** \brief Get the link transform w.r.t. the root link (model frame) of the RobotModel.
12371238
* This is typically the root link of the URDF unless a virtual joint is present.
@@ -1712,6 +1713,13 @@ class RobotState
17121713
/** \brief This function is only called in debug mode */
17131714
bool checkCollisionTransforms() const;
17141715

1716+
/** \brief Get the closest link in the kinematic tree to `frame`.
1717+
*
1718+
* Helper function for getRigidlyConnectedParentLinkModel,
1719+
* which resolves attached objects / subframes.
1720+
*/
1721+
const moveit::core::LinkModel* getLinkModelIncludingAttachedBodies(const std::string& frame) const;
1722+
17151723
RobotModelConstPtr robot_model_;
17161724

17171725
std::vector<double> position_;

moveit_core/robot_state/src/cartesian_interpolator.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -455,6 +455,7 @@ CartesianInterpolator::Percentage CartesianInterpolator::computeCartesianPath(
455455
if (start_state->setFromIK(group, pose * offset, link->getName(), consistency_limits, 0.0, validCallback, options,
456456
cost_function))
457457
{
458+
start_state->update();
458459
path.push_back(std::make_shared<moveit::core::RobotState>(*start_state));
459460
}
460461
else

0 commit comments

Comments
 (0)